mirror of https://github.com/ArduPilot/ardupilot
Merge branch 'master' of https://code.google.com/p/ardupilot-mega
This commit is contained in:
commit
59957e0c84
|
@ -18,6 +18,7 @@
|
||||||
HEXA_FRAME
|
HEXA_FRAME
|
||||||
Y6_FRAME
|
Y6_FRAME
|
||||||
OCTA_FRAME
|
OCTA_FRAME
|
||||||
|
OCTA_QUAD_FRAME
|
||||||
HELI_FRAME
|
HELI_FRAME
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
@ -89,3 +90,5 @@
|
||||||
// #define MOT_7 CH_7
|
// #define MOT_7 CH_7
|
||||||
// #define MOT_8 CH_8
|
// #define MOT_8 CH_8
|
||||||
|
|
||||||
|
// Enabling this will use the GPS lat/long coordinate to get the compass declination
|
||||||
|
//#define AUTOMATIC_DECLINATION ENABLED
|
|
@ -1,6 +1,6 @@
|
||||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||||
|
|
||||||
#define THISFIRMWARE "ArduCopter V2.4.1"
|
#define THISFIRMWARE "ArduCopter V2.4.2"
|
||||||
/*
|
/*
|
||||||
ArduCopter Version 2.4
|
ArduCopter Version 2.4
|
||||||
Authors: Jason Short
|
Authors: Jason Short
|
||||||
|
@ -35,6 +35,7 @@ Jean-Louis Naudin :Auto Landing
|
||||||
Sandro Benigno :Camera support
|
Sandro Benigno :Camera support
|
||||||
Olivier Adler :PPM Encoder
|
Olivier Adler :PPM Encoder
|
||||||
John Arne Birkeland :PPM Encoder
|
John Arne Birkeland :PPM Encoder
|
||||||
|
Adam M Rivera :Auto Compass Declination
|
||||||
|
|
||||||
And much more so PLEASE PM me on DIYDRONES to add your contribution to the List
|
And much more so PLEASE PM me on DIYDRONES to add your contribution to the List
|
||||||
|
|
||||||
|
@ -72,6 +73,7 @@ http://code.google.com/p/ardupilot-mega/downloads/list
|
||||||
#include <AP_PeriodicProcess.h> // Parent header of Timer
|
#include <AP_PeriodicProcess.h> // Parent header of Timer
|
||||||
// (only included for makefile libpath to work)
|
// (only included for makefile libpath to work)
|
||||||
#include <AP_TimerProcess.h> // TimerProcess is the scheduler for MPU6000 reads.
|
#include <AP_TimerProcess.h> // TimerProcess is the scheduler for MPU6000 reads.
|
||||||
|
#include <AP_Quaternion.h> // Madgwick quaternion system
|
||||||
#include <AP_DCM.h> // ArduPilot Mega DCM Library
|
#include <AP_DCM.h> // ArduPilot Mega DCM Library
|
||||||
#include <APM_PI.h> // PI library
|
#include <APM_PI.h> // PI library
|
||||||
#include <AC_PID.h> // PID library
|
#include <AC_PID.h> // PID library
|
||||||
|
@ -94,6 +96,11 @@ http://code.google.com/p/ardupilot-mega/downloads/list
|
||||||
#include "Parameters.h"
|
#include "Parameters.h"
|
||||||
#include "GCS.h"
|
#include "GCS.h"
|
||||||
|
|
||||||
|
#if AUTOMATIC_DECLINATION == ENABLED
|
||||||
|
// this is in an #if to avoid the static data
|
||||||
|
#include <AP_Declination.h> // ArduPilot Mega Declination Helper Library
|
||||||
|
#endif
|
||||||
|
|
||||||
////////////////////////////////////////////////////////////////////////////////
|
////////////////////////////////////////////////////////////////////////////////
|
||||||
// Serial ports
|
// Serial ports
|
||||||
////////////////////////////////////////////////////////////////////////////////
|
////////////////////////////////////////////////////////////////////////////////
|
||||||
|
@ -222,12 +229,21 @@ AP_InertialSensor_MPU6000 ins( CONFIG_MPU6000_CHIP_SELECT_PIN );
|
||||||
AP_InertialSensor_Oilpan ins(&adc);
|
AP_InertialSensor_Oilpan ins(&adc);
|
||||||
#endif
|
#endif
|
||||||
AP_IMU_INS imu(&ins);
|
AP_IMU_INS imu(&ins);
|
||||||
|
|
||||||
// we don't want to use gps for yaw correction on ArduCopter, so pass
|
// we don't want to use gps for yaw correction on ArduCopter, so pass
|
||||||
// a NULL GPS object pointer
|
// a NULL GPS object pointer
|
||||||
static GPS *g_gps_null;
|
static GPS *g_gps_null;
|
||||||
AP_DCM dcm(&imu, g_gps_null);
|
|
||||||
AP_TimerProcess timer_scheduler;
|
|
||||||
|
|
||||||
|
#if QUATERNION_ENABLE == ENABLED
|
||||||
|
// this shouldn't be called dcm of course, but until we
|
||||||
|
// decide to actually use something else, I don't want the patch
|
||||||
|
// size to be huge
|
||||||
|
AP_Quaternion dcm(&imu, g_gps_null);
|
||||||
|
#else
|
||||||
|
AP_DCM dcm(&imu, g_gps_null);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
AP_TimerProcess timer_scheduler;
|
||||||
#elif HIL_MODE == HIL_MODE_SENSORS
|
#elif HIL_MODE == HIL_MODE_SENSORS
|
||||||
// sensor emulators
|
// sensor emulators
|
||||||
AP_ADC_HIL adc;
|
AP_ADC_HIL adc;
|
||||||
|
@ -325,6 +341,9 @@ static const char* flight_mode_strings[] = {
|
||||||
static int16_t x_actual_speed;
|
static int16_t x_actual_speed;
|
||||||
static int16_t y_actual_speed;
|
static int16_t y_actual_speed;
|
||||||
|
|
||||||
|
static int16_t x_rate_d;
|
||||||
|
static int16_t y_rate_d;
|
||||||
|
|
||||||
// The difference between the desired rate of travel and the actual rate of travel
|
// The difference between the desired rate of travel and the actual rate of travel
|
||||||
// updated after GPS read - 5-10hz
|
// updated after GPS read - 5-10hz
|
||||||
static int16_t x_rate_error;
|
static int16_t x_rate_error;
|
||||||
|
@ -502,10 +521,17 @@ static int32_t initial_simple_bearing;
|
||||||
// Used to control Axis lock
|
// Used to control Axis lock
|
||||||
int32_t roll_axis;
|
int32_t roll_axis;
|
||||||
int32_t pitch_axis;
|
int32_t pitch_axis;
|
||||||
|
|
||||||
// Filters
|
// Filters
|
||||||
AverageFilterInt32_Size3 roll_rate_d_filter; // filtered acceleration
|
AverageFilterInt32_Size3 roll_rate_d_filter; // filtered acceleration
|
||||||
AverageFilterInt32_Size3 pitch_rate_d_filter; // filtered pitch acceleration
|
AverageFilterInt32_Size3 pitch_rate_d_filter; // filtered pitch acceleration
|
||||||
|
|
||||||
|
AverageFilterInt16_Size3 lat_rate_d_filter; // for filtering D term
|
||||||
|
AverageFilterInt16_Size3 lon_rate_d_filter; // for filtering D term
|
||||||
|
|
||||||
|
// Barometer filter
|
||||||
|
AverageFilterInt32_Size5 baro_filter; // filtered pitch acceleration
|
||||||
|
|
||||||
////////////////////////////////////////////////////////////////////////////////
|
////////////////////////////////////////////////////////////////////////////////
|
||||||
// Circle Mode / Loiter control
|
// Circle Mode / Loiter control
|
||||||
////////////////////////////////////////////////////////////////////////////////
|
////////////////////////////////////////////////////////////////////////////////
|
||||||
|
@ -568,7 +594,11 @@ static int32_t ground_pressure;
|
||||||
static int16_t ground_temperature;
|
static int16_t ground_temperature;
|
||||||
// The cm we are off in altitude from next_WP.alt – Positive value means we are below the WP
|
// The cm we are off in altitude from next_WP.alt – Positive value means we are below the WP
|
||||||
static int32_t altitude_error;
|
static int32_t altitude_error;
|
||||||
// The cm/s we are moving up or down - Positive = UP
|
// The cm/s we are moving up or down based on sensor data - Positive = UP
|
||||||
|
static int16_t climb_rate_actual;
|
||||||
|
// Used to dither our climb_rate over 50hz
|
||||||
|
static int16_t climb_rate_error;
|
||||||
|
// The cm/s we are moving up or down based on filtered data - Positive = UP
|
||||||
static int16_t climb_rate;
|
static int16_t climb_rate;
|
||||||
// The altitude as reported by Sonar in cm – Values are 20 to 700 generally.
|
// The altitude as reported by Sonar in cm – Values are 20 to 700 generally.
|
||||||
static int16_t sonar_alt;
|
static int16_t sonar_alt;
|
||||||
|
@ -578,8 +608,10 @@ static int16_t sonar_rate;
|
||||||
static int32_t baro_alt;
|
static int32_t baro_alt;
|
||||||
// The climb_rate as reported by Baro in cm/s
|
// The climb_rate as reported by Baro in cm/s
|
||||||
static int16_t baro_rate;
|
static int16_t baro_rate;
|
||||||
//
|
// used to switch out of Manual Boost
|
||||||
static boolean reset_throttle_flag;
|
static boolean reset_throttle_flag;
|
||||||
|
// used to track when to read sensors vs estimate alt
|
||||||
|
static boolean alt_sensor_flag;
|
||||||
|
|
||||||
|
|
||||||
////////////////////////////////////////////////////////////////////////////////
|
////////////////////////////////////////////////////////////////////////////////
|
||||||
|
@ -690,13 +722,6 @@ static int16_t nav_throttle; // 0-1000 for throttle control
|
||||||
// This is a simple counter to track the amount of throttle used during flight
|
// This is a simple counter to track the amount of throttle used during flight
|
||||||
// This could be useful later in determining and debuging current usage and predicting battery life
|
// This could be useful later in determining and debuging current usage and predicting battery life
|
||||||
static uint32_t throttle_integrator;
|
static uint32_t throttle_integrator;
|
||||||
// This is a future value for replacing the throttle_cruise setup procedure. It's an average of throttle control
|
|
||||||
// that is generated when the climb rate is within a certain threshold
|
|
||||||
//static float throttle_avg = THROTTLE_CRUISE;
|
|
||||||
// This is a flag used to trigger the updating of nav_throttle at 10hz
|
|
||||||
static bool invalid_throttle;
|
|
||||||
// Used to track the altitude offset for climbrate control
|
|
||||||
//static int32_t target_altitude;
|
|
||||||
|
|
||||||
////////////////////////////////////////////////////////////////////////////////
|
////////////////////////////////////////////////////////////////////////////////
|
||||||
// Climb rate control
|
// Climb rate control
|
||||||
|
@ -839,9 +864,10 @@ void setup() {
|
||||||
void loop()
|
void loop()
|
||||||
{
|
{
|
||||||
uint32_t timer = micros();
|
uint32_t timer = micros();
|
||||||
|
|
||||||
// We want this to execute fast
|
// We want this to execute fast
|
||||||
// ----------------------------
|
// ----------------------------
|
||||||
if ((timer - fast_loopTimer) >= 4000) {
|
if ((timer - fast_loopTimer) >= 10000 && imu.new_data_available()) {
|
||||||
//Log_Write_Data(13, (int32_t)(timer - fast_loopTimer));
|
//Log_Write_Data(13, (int32_t)(timer - fast_loopTimer));
|
||||||
|
|
||||||
//PORTK |= B00010000;
|
//PORTK |= B00010000;
|
||||||
|
@ -957,8 +983,10 @@ static void medium_loop()
|
||||||
#if HIL_MODE != HIL_MODE_ATTITUDE // don't execute in HIL mode
|
#if HIL_MODE != HIL_MODE_ATTITUDE // don't execute in HIL mode
|
||||||
if(g.compass_enabled){
|
if(g.compass_enabled){
|
||||||
if (compass.read()) {
|
if (compass.read()) {
|
||||||
compass.calculate(dcm.get_dcm_matrix()); // Calculate heading
|
// Calculate heading
|
||||||
compass.null_offsets(dcm.get_dcm_matrix());
|
Matrix3f m = dcm.get_dcm_matrix();
|
||||||
|
compass.calculate(m);
|
||||||
|
compass.null_offsets(m);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
@ -1005,8 +1033,9 @@ static void medium_loop()
|
||||||
// -----------------------------
|
// -----------------------------
|
||||||
update_navigation();
|
update_navigation();
|
||||||
|
|
||||||
if (g.log_bitmask & MASK_LOG_NTUN)
|
if (g.log_bitmask & MASK_LOG_NTUN && motor_armed){
|
||||||
Log_Write_Nav_Tuning();
|
Log_Write_Nav_Tuning();
|
||||||
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
@ -1018,13 +1047,10 @@ static void medium_loop()
|
||||||
|
|
||||||
// Read altitude from sensors
|
// Read altitude from sensors
|
||||||
// --------------------------
|
// --------------------------
|
||||||
#if HIL_MODE != HIL_MODE_ATTITUDE // don't execute in HIL mode
|
//#if HIL_MODE != HIL_MODE_ATTITUDE // don't execute in HIL mode
|
||||||
update_altitude();
|
//update_altitude();
|
||||||
#endif
|
//#endif
|
||||||
|
alt_sensor_flag = true;
|
||||||
// invalidate the throttle hold value
|
|
||||||
// ----------------------------------
|
|
||||||
invalid_throttle = true;
|
|
||||||
|
|
||||||
break;
|
break;
|
||||||
|
|
||||||
|
@ -1045,16 +1071,13 @@ static void medium_loop()
|
||||||
if (g.log_bitmask & MASK_LOG_ATTITUDE_MED)
|
if (g.log_bitmask & MASK_LOG_ATTITUDE_MED)
|
||||||
Log_Write_Attitude();
|
Log_Write_Attitude();
|
||||||
|
|
||||||
if (g.log_bitmask & MASK_LOG_CTUN)
|
if (g.log_bitmask & MASK_LOG_MOTORS)
|
||||||
Log_Write_Control_Tuning();
|
Log_Write_Motors();
|
||||||
}
|
}
|
||||||
|
|
||||||
// send all requested output streams with rates requested
|
// send all requested output streams with rates requested
|
||||||
// between 5 and 45 Hz
|
// between 5 and 45 Hz
|
||||||
gcs_data_stream_send(5,45);
|
gcs_data_stream_send(5,45);
|
||||||
|
|
||||||
if (g.log_bitmask & MASK_LOG_MOTORS)
|
|
||||||
Log_Write_Motors();
|
|
||||||
|
|
||||||
break;
|
break;
|
||||||
|
|
||||||
|
@ -1076,8 +1099,8 @@ static void medium_loop()
|
||||||
// -----------------------
|
// -----------------------
|
||||||
arm_motors();
|
arm_motors();
|
||||||
|
|
||||||
// Do an extra baro read
|
// Do an extra baro read for Temp sensing
|
||||||
// ---------------------
|
// ---------------------------------------
|
||||||
#if HIL_MODE != HIL_MODE_ATTITUDE
|
#if HIL_MODE != HIL_MODE_ATTITUDE
|
||||||
barometer.read();
|
barometer.read();
|
||||||
#endif
|
#endif
|
||||||
|
@ -1102,6 +1125,10 @@ static void medium_loop()
|
||||||
// ---------------------------
|
// ---------------------------
|
||||||
static void fifty_hz_loop()
|
static void fifty_hz_loop()
|
||||||
{
|
{
|
||||||
|
// read altitude sensors or estimate altitude
|
||||||
|
// ------------------------------------------
|
||||||
|
update_altitude_est();
|
||||||
|
|
||||||
// moved to slower loop
|
// moved to slower loop
|
||||||
// --------------------
|
// --------------------
|
||||||
update_throttle_mode();
|
update_throttle_mode();
|
||||||
|
@ -1162,6 +1189,11 @@ static void slow_loop()
|
||||||
slow_loopCounter++;
|
slow_loopCounter++;
|
||||||
superslow_loopCounter++;
|
superslow_loopCounter++;
|
||||||
|
|
||||||
|
// update throttle hold every 20 seconds
|
||||||
|
if(superslow_loopCounter > 60){
|
||||||
|
update_throttle_cruise();
|
||||||
|
}
|
||||||
|
|
||||||
if(superslow_loopCounter > 1200){
|
if(superslow_loopCounter > 1200){
|
||||||
#if HIL_MODE != HIL_MODE_ATTITUDE
|
#if HIL_MODE != HIL_MODE_ATTITUDE
|
||||||
if(g.rc_3.control_in == 0 && control_mode == STABILIZE && g.compass_enabled){
|
if(g.rc_3.control_in == 0 && control_mode == STABILIZE && g.compass_enabled){
|
||||||
|
@ -1219,13 +1251,14 @@ static void slow_loop()
|
||||||
// 1Hz loop
|
// 1Hz loop
|
||||||
static void super_slow_loop()
|
static void super_slow_loop()
|
||||||
{
|
{
|
||||||
if (g.log_bitmask & MASK_LOG_CUR)
|
if (g.log_bitmask & MASK_LOG_CUR && motor_armed)
|
||||||
Log_Write_Current();
|
Log_Write_Current();
|
||||||
|
|
||||||
// this function disarms the copter if it has been sitting on the ground for any moment of time greater than 30s
|
// this function disarms the copter if it has been sitting on the ground for any moment of time greater than 30s
|
||||||
// but only of the control mode is manual
|
// but only of the control mode is manual
|
||||||
if((control_mode <= ACRO) && (g.rc_3.control_in == 0)){
|
if((control_mode <= ACRO) && (g.rc_3.control_in == 0)){
|
||||||
auto_disarming_counter++;
|
auto_disarming_counter++;
|
||||||
|
|
||||||
if(auto_disarming_counter == AUTO_ARMING_DELAY){
|
if(auto_disarming_counter == AUTO_ARMING_DELAY){
|
||||||
init_disarm_motors();
|
init_disarm_motors();
|
||||||
}else if (auto_disarming_counter > AUTO_ARMING_DELAY){
|
}else if (auto_disarming_counter > AUTO_ARMING_DELAY){
|
||||||
|
@ -1234,8 +1267,10 @@ static void super_slow_loop()
|
||||||
}else{
|
}else{
|
||||||
auto_disarming_counter = 0;
|
auto_disarming_counter = 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
gcs_send_message(MSG_HEARTBEAT);
|
gcs_send_message(MSG_HEARTBEAT);
|
||||||
gcs_data_stream_send(1,3);
|
gcs_data_stream_send(1,3);
|
||||||
|
|
||||||
// agmatthews - USERHOOKS
|
// agmatthews - USERHOOKS
|
||||||
#ifdef USERHOOK_SUPERSLOWLOOP
|
#ifdef USERHOOK_SUPERSLOWLOOP
|
||||||
USERHOOK_SUPERSLOWLOOP
|
USERHOOK_SUPERSLOWLOOP
|
||||||
|
@ -1350,6 +1385,12 @@ static void update_GPS(void)
|
||||||
ground_start_count = 5;
|
ground_start_count = 5;
|
||||||
|
|
||||||
}else{
|
}else{
|
||||||
|
#if AUTOMATIC_DECLINATION == ENABLED
|
||||||
|
if(g.compass_enabled) {
|
||||||
|
// Set compass declination automatically
|
||||||
|
compass.set_initial_location(g_gps->latitude, g_gps->longitude, false);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
// save home to eeprom (we must have a good fix to have reached this point)
|
// save home to eeprom (we must have a good fix to have reached this point)
|
||||||
init_home();
|
init_home();
|
||||||
ground_start_count = 0;
|
ground_start_count = 0;
|
||||||
|
@ -1359,14 +1400,14 @@ static void update_GPS(void)
|
||||||
current_loc.lng = g_gps->longitude; // Lon * 10 * *7
|
current_loc.lng = g_gps->longitude; // Lon * 10 * *7
|
||||||
current_loc.lat = g_gps->latitude; // Lat * 10 * *7
|
current_loc.lat = g_gps->latitude; // Lat * 10 * *7
|
||||||
|
|
||||||
if (g.log_bitmask & MASK_LOG_GPS){
|
if (g.log_bitmask & MASK_LOG_GPS && motor_armed){
|
||||||
Log_Write_GPS();
|
Log_Write_GPS();
|
||||||
}
|
}
|
||||||
|
|
||||||
#if HIL_MODE == HIL_MODE_ATTITUDE // only execute in HIL mode
|
#if HIL_MODE == HIL_MODE_ATTITUDE // only execute in HIL mode
|
||||||
update_altitude();
|
//update_altitude();
|
||||||
|
alt_sensor_flag = true;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -1633,12 +1674,12 @@ void update_throttle_mode(void)
|
||||||
// we are under automatic throttle control
|
// we are under automatic throttle control
|
||||||
// ---------------------------------------
|
// ---------------------------------------
|
||||||
if(reset_throttle_flag) {
|
if(reset_throttle_flag) {
|
||||||
set_new_altitude(max(current_loc.alt, 100));
|
force_new_altitude(max(current_loc.alt, 100));
|
||||||
reset_throttle_flag = false;
|
reset_throttle_flag = false;
|
||||||
|
update_throttle_cruise();
|
||||||
}
|
}
|
||||||
|
|
||||||
// 10hz, don't run up i term
|
if(motor_auto_armed == true){
|
||||||
if(invalid_throttle && motor_auto_armed == true){
|
|
||||||
|
|
||||||
// how far off are we
|
// how far off are we
|
||||||
altitude_error = get_altitude_error();
|
altitude_error = get_altitude_error();
|
||||||
|
@ -1646,8 +1687,6 @@ void update_throttle_mode(void)
|
||||||
// get the AP throttle
|
// get the AP throttle
|
||||||
nav_throttle = get_nav_throttle(altitude_error);
|
nav_throttle = get_nav_throttle(altitude_error);
|
||||||
|
|
||||||
// clear the new data flag
|
|
||||||
invalid_throttle = false;
|
|
||||||
/*
|
/*
|
||||||
Serial.printf("tar_alt: %d, actual_alt: %d \talt_err: %d, \tnav_thr: %d, \talt Int: %d\n",
|
Serial.printf("tar_alt: %d, actual_alt: %d \talt_err: %d, \tnav_thr: %d, \talt Int: %d\n",
|
||||||
next_WP.alt,
|
next_WP.alt,
|
||||||
|
@ -1656,6 +1695,7 @@ void update_throttle_mode(void)
|
||||||
nav_throttle,
|
nav_throttle,
|
||||||
(int16_t)g.pi_alt_hold.get_integrator());
|
(int16_t)g.pi_alt_hold.get_integrator());
|
||||||
//*/
|
//*/
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// hack to remove the influence of the ground effect
|
// hack to remove the influence of the ground effect
|
||||||
|
@ -1829,7 +1869,7 @@ static void read_AHRS(void)
|
||||||
gcs_update();
|
gcs_update();
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
dcm.update_DCM_fast();
|
dcm.update_DCM();
|
||||||
omega = imu.get_gyro();
|
omega = imu.get_gyro();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -1864,7 +1904,6 @@ static void update_altitude()
|
||||||
{
|
{
|
||||||
static int16_t old_sonar_alt = 0;
|
static int16_t old_sonar_alt = 0;
|
||||||
static int32_t old_baro_alt = 0;
|
static int32_t old_baro_alt = 0;
|
||||||
static int16_t old_climb_rate = 0;
|
|
||||||
|
|
||||||
#if HIL_MODE == HIL_MODE_ATTITUDE
|
#if HIL_MODE == HIL_MODE_ATTITUDE
|
||||||
// we are in the SIM, fake out the baro and Sonar
|
// we are in the SIM, fake out the baro and Sonar
|
||||||
|
@ -1879,7 +1918,8 @@ static void update_altitude()
|
||||||
// This is real life
|
// This is real life
|
||||||
|
|
||||||
// read in Actual Baro Altitude
|
// read in Actual Baro Altitude
|
||||||
baro_alt = (baro_alt + read_barometer()) >> 1;
|
baro_alt = read_barometer();
|
||||||
|
//Serial.printf("baro_alt: %d \n", baro_alt);
|
||||||
|
|
||||||
// calc the vertical accel rate
|
// calc the vertical accel rate
|
||||||
int temp = (baro_alt - old_baro_alt) * 10;
|
int temp = (baro_alt - old_baro_alt) * 10;
|
||||||
|
@ -1889,7 +1929,6 @@ static void update_altitude()
|
||||||
// Note: sonar_alt is calculated in a faster loop and filtered with a mode filter
|
// Note: sonar_alt is calculated in a faster loop and filtered with a mode filter
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
||||||
if(g.sonar_enabled){
|
if(g.sonar_enabled){
|
||||||
// filter out offset
|
// filter out offset
|
||||||
float scale;
|
float scale;
|
||||||
|
@ -1921,48 +1960,60 @@ static void update_altitude()
|
||||||
current_loc.alt = ((float)sonar_alt * (1.0 - scale)) + ((float)baro_alt * scale) + home.alt;
|
current_loc.alt = ((float)sonar_alt * (1.0 - scale)) + ((float)baro_alt * scale) + home.alt;
|
||||||
|
|
||||||
// solve for a blended climb_rate
|
// solve for a blended climb_rate
|
||||||
climb_rate = ((float)sonar_rate * (1.0 - scale)) + (float)baro_rate * scale;
|
climb_rate_actual = ((float)sonar_rate * (1.0 - scale)) + (float)baro_rate * scale;
|
||||||
|
|
||||||
}else{
|
}else{
|
||||||
// we must be higher than sonar (>800), don't get tricked by bad sonar reads
|
// we must be higher than sonar (>800), don't get tricked by bad sonar reads
|
||||||
current_loc.alt = baro_alt + home.alt; // home alt = 0
|
current_loc.alt = baro_alt + home.alt; // home alt = 0
|
||||||
// dont blend, go straight baro
|
// dont blend, go straight baro
|
||||||
climb_rate = baro_rate;
|
climb_rate_actual = baro_rate;
|
||||||
}
|
}
|
||||||
|
|
||||||
}else{
|
}else{
|
||||||
// NO Sonar case
|
// NO Sonar case
|
||||||
current_loc.alt = baro_alt + home.alt;
|
current_loc.alt = baro_alt + home.alt;
|
||||||
climb_rate = baro_rate;
|
climb_rate_actual = baro_rate;
|
||||||
}
|
}
|
||||||
|
|
||||||
// simple smoothing
|
|
||||||
climb_rate = (climb_rate + old_climb_rate)>>1;
|
|
||||||
|
|
||||||
// manage bad data
|
|
||||||
climb_rate = constrain(climb_rate, -800, 800);
|
|
||||||
|
|
||||||
// save for filtering
|
|
||||||
old_climb_rate = climb_rate;
|
|
||||||
|
|
||||||
// update the target altitude
|
// update the target altitude
|
||||||
next_WP.alt = get_new_altitude();
|
next_WP.alt = get_new_altitude();
|
||||||
|
|
||||||
|
// calc error
|
||||||
|
climb_rate_error = (climb_rate_actual - climb_rate) / 5;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
static void update_altitude_est()
|
||||||
|
{
|
||||||
|
if(alt_sensor_flag){
|
||||||
|
update_altitude();
|
||||||
|
alt_sensor_flag = false;
|
||||||
|
|
||||||
|
if(g.log_bitmask & MASK_LOG_CTUN && motor_armed){
|
||||||
|
Log_Write_Control_Tuning();
|
||||||
|
}
|
||||||
|
|
||||||
|
}else{
|
||||||
|
// simple dithering of climb rate
|
||||||
|
climb_rate += climb_rate_error;
|
||||||
|
current_loc.alt += (climb_rate / 50);
|
||||||
|
}
|
||||||
|
//Serial.printf(" %d, %d, %d, %d\n", climb_rate_actual, climb_rate_error, climb_rate, current_loc.alt);
|
||||||
|
}
|
||||||
|
|
||||||
|
#define THROTTLE_ADJUST 225
|
||||||
static void
|
static void
|
||||||
adjust_altitude()
|
adjust_altitude()
|
||||||
{
|
{
|
||||||
if(g.rc_3.control_in <= (MINIMUM_THROTTLE + 100)){
|
if(g.rc_3.control_in <= (MINIMUM_THROTTLE + THROTTLE_ADJUST)){
|
||||||
// we remove 0 to 100 PWM from hover
|
// we remove 0 to 100 PWM from hover
|
||||||
manual_boost = (g.rc_3.control_in - MINIMUM_THROTTLE) -100;
|
manual_boost = (g.rc_3.control_in - MINIMUM_THROTTLE) - THROTTLE_ADJUST;
|
||||||
manual_boost = max(-100, manual_boost);
|
manual_boost = max(-THROTTLE_ADJUST, manual_boost);
|
||||||
update_throttle_cruise();
|
|
||||||
|
|
||||||
}else if (g.rc_3.control_in >= (MAXIMUM_THROTTLE - 100)){
|
}else if (g.rc_3.control_in >= (MAXIMUM_THROTTLE - THROTTLE_ADJUST)){
|
||||||
// we add 0 to 100 PWM to hover
|
// we add 0 to 100 PWM to hover
|
||||||
manual_boost = g.rc_3.control_in - (MAXIMUM_THROTTLE - 100);
|
manual_boost = g.rc_3.control_in - (MAXIMUM_THROTTLE - THROTTLE_ADJUST);
|
||||||
manual_boost = min(100, manual_boost);
|
manual_boost = min(THROTTLE_ADJUST, manual_boost);
|
||||||
update_throttle_cruise();
|
|
||||||
}else {
|
}else {
|
||||||
manual_boost = 0;
|
manual_boost = 0;
|
||||||
}
|
}
|
||||||
|
@ -2044,6 +2095,11 @@ static void tuning(){
|
||||||
g.pid_loiter_rate_lat.kP(tuning_value);
|
g.pid_loiter_rate_lat.kP(tuning_value);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
|
case CH6_LOITER_RATE_D:
|
||||||
|
g.pid_loiter_rate_lon.kD(tuning_value);
|
||||||
|
g.pid_loiter_rate_lat.kD(tuning_value);
|
||||||
|
break;
|
||||||
|
|
||||||
case CH6_NAV_I:
|
case CH6_NAV_I:
|
||||||
g.pid_nav_lat.kI(tuning_value);
|
g.pid_nav_lat.kI(tuning_value);
|
||||||
g.pid_nav_lon.kI(tuning_value);
|
g.pid_nav_lon.kI(tuning_value);
|
||||||
|
@ -2152,8 +2208,8 @@ static void update_nav_wp()
|
||||||
// or change Loiter position
|
// or change Loiter position
|
||||||
|
|
||||||
// We bring copy over our Iterms for wind control, but we don't navigate
|
// We bring copy over our Iterms for wind control, but we don't navigate
|
||||||
nav_lon = g.pi_loiter_lon.get_integrator();
|
nav_lon = g.pid_loiter_rate_lon.get_integrator();
|
||||||
nav_lat = g.pi_loiter_lat.get_integrator();
|
nav_lat = g.pid_loiter_rate_lon.get_integrator();
|
||||||
|
|
||||||
// rotate pitch and roll to the copter frame of reference
|
// rotate pitch and roll to the copter frame of reference
|
||||||
calc_loiter_pitch_roll();
|
calc_loiter_pitch_roll();
|
||||||
|
|
|
@ -186,31 +186,35 @@ get_rate_yaw(int32_t target_rate)
|
||||||
static int16_t
|
static int16_t
|
||||||
get_nav_throttle(int32_t z_error)
|
get_nav_throttle(int32_t z_error)
|
||||||
{
|
{
|
||||||
static int16_t old_output = 0;
|
//static int16_t old_output = 0;
|
||||||
int16_t rate_error = 0;
|
int16_t rate_error = 0;
|
||||||
int16_t output = 0;
|
int16_t output = 0;
|
||||||
|
|
||||||
// convert to desired Rate:
|
// convert to desired Rate:
|
||||||
rate_error = g.pi_alt_hold.get_p(z_error);
|
rate_error = g.pi_alt_hold.get_p(z_error);
|
||||||
rate_error = constrain(rate_error, -150, 150);
|
rate_error = constrain(rate_error, -250, 250);
|
||||||
|
|
||||||
// limit error to prevent I term wind up
|
// limit error to prevent I term wind up
|
||||||
z_error = constrain(z_error, -400, 400);
|
z_error = constrain(z_error, -400, 400);
|
||||||
|
|
||||||
// compensates throttle setpoint error for hovering
|
// compensates throttle setpoint error for hovering
|
||||||
int16_t iterm = g.pi_alt_hold.get_i(z_error, .1);
|
int16_t iterm = g.pi_alt_hold.get_i(z_error, .02);
|
||||||
|
|
||||||
// calculate rate error
|
// calculate rate error
|
||||||
rate_error = rate_error - climb_rate;
|
rate_error = rate_error - climb_rate;
|
||||||
|
|
||||||
|
// hack to see if we can smooth out oscillations
|
||||||
|
//if(rate_error < 0)
|
||||||
|
// rate_error = rate_error >> 1;
|
||||||
|
|
||||||
// limit the rate
|
// limit the rate
|
||||||
output = constrain(g.pid_throttle.get_pid(rate_error, .1), -160, 180);
|
output = constrain(g.pid_throttle.get_pid(rate_error, .02), -80, 120);
|
||||||
|
|
||||||
// light filter of output
|
// light filter of output
|
||||||
output = (old_output + output) / 2;
|
//output = (old_output + output) / 2;
|
||||||
|
|
||||||
// save our output
|
// save our output
|
||||||
old_output = output;
|
//old_output = output;
|
||||||
|
|
||||||
// output control:
|
// output control:
|
||||||
return output + iterm;
|
return output + iterm;
|
||||||
|
@ -219,8 +223,6 @@ get_nav_throttle(int32_t z_error)
|
||||||
// Keeps old data out of our calculation / logs
|
// Keeps old data out of our calculation / logs
|
||||||
static void reset_nav_params(void)
|
static void reset_nav_params(void)
|
||||||
{
|
{
|
||||||
// forces us to update nav throttle
|
|
||||||
invalid_throttle = true;
|
|
||||||
nav_throttle = 0;
|
nav_throttle = 0;
|
||||||
|
|
||||||
// always start Circle mode at same angle
|
// always start Circle mode at same angle
|
||||||
|
|
|
@ -124,6 +124,42 @@ static void NOINLINE send_nav_controller_output(mavlink_channel_t chan)
|
||||||
crosstrack_error); // was 0
|
crosstrack_error); // was 0
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#if HIL_MODE != HIL_MODE_ATTITUDE
|
||||||
|
static void NOINLINE send_dcm(mavlink_channel_t chan)
|
||||||
|
{
|
||||||
|
Vector3f omega_I = dcm.get_gyro_drift();
|
||||||
|
mavlink_msg_dcm_send(
|
||||||
|
chan,
|
||||||
|
omega_I.x,
|
||||||
|
omega_I.y,
|
||||||
|
omega_I.z,
|
||||||
|
dcm.get_accel_weight(),
|
||||||
|
dcm.get_renorm_val(),
|
||||||
|
dcm.get_error_rp(),
|
||||||
|
dcm.get_error_yaw());
|
||||||
|
}
|
||||||
|
#endif // HIL_MODE != HIL_MODE_ATTITUDE
|
||||||
|
|
||||||
|
#ifdef DESKTOP_BUILD
|
||||||
|
// report simulator state
|
||||||
|
static void NOINLINE send_simstate(mavlink_channel_t chan)
|
||||||
|
{
|
||||||
|
extern void sitl_simstate_send(uint8_t chan);
|
||||||
|
sitl_simstate_send((uint8_t)chan);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifndef DESKTOP_BUILD
|
||||||
|
static void NOINLINE send_hwstatus(mavlink_channel_t chan)
|
||||||
|
{
|
||||||
|
mavlink_msg_hwstatus_send(
|
||||||
|
chan,
|
||||||
|
board_voltage(),
|
||||||
|
I2c.lockup_count());
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
|
||||||
static void NOINLINE send_gps_raw(mavlink_channel_t chan)
|
static void NOINLINE send_gps_raw(mavlink_channel_t chan)
|
||||||
{
|
{
|
||||||
mavlink_msg_gps_raw_send(
|
mavlink_msg_gps_raw_send(
|
||||||
|
@ -435,6 +471,27 @@ static bool mavlink_try_send_message(mavlink_channel_t chan, enum ap_message id,
|
||||||
send_statustext(chan);
|
send_statustext(chan);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
|
case MSG_DCM:
|
||||||
|
#if HIL_MODE != HIL_MODE_ATTITUDE
|
||||||
|
CHECK_PAYLOAD_SIZE(DCM);
|
||||||
|
send_dcm(chan);
|
||||||
|
#endif
|
||||||
|
break;
|
||||||
|
|
||||||
|
case MSG_SIMSTATE:
|
||||||
|
#ifdef DESKTOP_BUILD
|
||||||
|
CHECK_PAYLOAD_SIZE(DCM);
|
||||||
|
send_simstate(chan);
|
||||||
|
#endif
|
||||||
|
break;
|
||||||
|
|
||||||
|
case MSG_HWSTATUS:
|
||||||
|
#ifndef DESKTOP_BUILD
|
||||||
|
CHECK_PAYLOAD_SIZE(HWSTATUS);
|
||||||
|
send_hwstatus(chan);
|
||||||
|
#endif
|
||||||
|
break;
|
||||||
|
|
||||||
case MSG_RETRY_DEFERRED:
|
case MSG_RETRY_DEFERRED:
|
||||||
break; // just here to prevent a warning
|
break; // just here to prevent a warning
|
||||||
}
|
}
|
||||||
|
@ -669,6 +726,7 @@ GCS_MAVLINK::data_stream_send(uint16_t freqMin, uint16_t freqMax)
|
||||||
|
|
||||||
if (freqLoopMatch(streamRateExtra1, freqMin, freqMax)){ // Use Extra 1 for AHRS info
|
if (freqLoopMatch(streamRateExtra1, freqMin, freqMax)){ // Use Extra 1 for AHRS info
|
||||||
send_message(MSG_ATTITUDE);
|
send_message(MSG_ATTITUDE);
|
||||||
|
send_message(MSG_SIMSTATE);
|
||||||
//Serial.printf("mav6 %d\n", (int)streamRateExtra1.get());
|
//Serial.printf("mav6 %d\n", (int)streamRateExtra1.get());
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -678,8 +736,8 @@ GCS_MAVLINK::data_stream_send(uint16_t freqMin, uint16_t freqMax)
|
||||||
}
|
}
|
||||||
|
|
||||||
if (freqLoopMatch(streamRateExtra3, freqMin, freqMax)){
|
if (freqLoopMatch(streamRateExtra3, freqMin, freqMax)){
|
||||||
// Available datastream
|
send_message(MSG_DCM);
|
||||||
//Serial.printf("mav8 %d\n", (int)streamRateExtra3.get());
|
send_message(MSG_HWSTATUS);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
|
@ -701,7 +701,7 @@ static void Log_Write_Attitude()
|
||||||
DataFlash.WriteInt((int)dcm.pitch_sensor); // 4
|
DataFlash.WriteInt((int)dcm.pitch_sensor); // 4
|
||||||
DataFlash.WriteInt(g.rc_4.control_in); // 5
|
DataFlash.WriteInt(g.rc_4.control_in); // 5
|
||||||
DataFlash.WriteInt((uint16_t)dcm.yaw_sensor); // 6
|
DataFlash.WriteInt((uint16_t)dcm.yaw_sensor); // 6
|
||||||
DataFlash.WriteInt((uint16_t)compass.heading); // 6
|
DataFlash.WriteInt((uint16_t)(wrap_360(ToDeg(compass.heading)*100))); // 7
|
||||||
|
|
||||||
DataFlash.WriteByte(END_BYTE);
|
DataFlash.WriteByte(END_BYTE);
|
||||||
}
|
}
|
||||||
|
@ -720,13 +720,13 @@ static void Log_Read_Attitude()
|
||||||
|
|
||||||
// 1 2 3 4 5 6 7
|
// 1 2 3 4 5 6 7
|
||||||
Serial.printf_P(PSTR("ATT, %d, %d, %d, %d, %d, %u, %u\n"),
|
Serial.printf_P(PSTR("ATT, %d, %d, %d, %d, %d, %u, %u\n"),
|
||||||
temp1,
|
(int)temp1,
|
||||||
temp2,
|
(int)temp2,
|
||||||
temp3,
|
(int)temp3,
|
||||||
temp4,
|
(int)temp4,
|
||||||
temp5,
|
(int)temp5,
|
||||||
temp6,
|
(unsigned int)temp6,
|
||||||
temp7);
|
(unsigned int)temp7);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Write a mode packet. Total length : 7 bytes
|
// Write a mode packet. Total length : 7 bytes
|
||||||
|
|
|
@ -42,6 +42,9 @@ sitl-hexa:
|
||||||
sitl-y6:
|
sitl-y6:
|
||||||
make -f ../libraries/Desktop/Makefile.desktop y6
|
make -f ../libraries/Desktop/Makefile.desktop y6
|
||||||
|
|
||||||
|
sitl-quaternion:
|
||||||
|
make -f ../libraries/Desktop/Makefile.desktop EXTRAFLAGS="-DQUATERNION_ENABLE=ENABLED"
|
||||||
|
|
||||||
etags:
|
etags:
|
||||||
cd .. && etags -f ArduCopter/TAGS --langmap=C++:.pde.cpp.h $$(git ls-files ArduCopter libraries)
|
cd .. && etags -f ArduCopter/TAGS --langmap=C++:.pde.cpp.h $$(git ls-files ArduCopter libraries)
|
||||||
|
|
||||||
|
|
|
@ -78,7 +78,8 @@ public:
|
||||||
k_param_heli_servo_averaging,
|
k_param_heli_servo_averaging,
|
||||||
k_param_heli_servo_manual,
|
k_param_heli_servo_manual,
|
||||||
k_param_heli_phase_angle,
|
k_param_heli_phase_angle,
|
||||||
k_param_heli_collective_yaw_effect, // 97
|
k_param_heli_collective_yaw_effect,
|
||||||
|
k_param_heli_h1_swash_enabled, //98
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// 110: Telemetry control
|
// 110: Telemetry control
|
||||||
|
@ -281,6 +282,7 @@ public:
|
||||||
AP_Int8 heli_servo_manual; // 0 = normal mode, 1 = radio inputs directly control swash. required for swash set-up
|
AP_Int8 heli_servo_manual; // 0 = normal mode, 1 = radio inputs directly control swash. required for swash set-up
|
||||||
AP_Int16 heli_phase_angle; // 0 to 360 degrees. specifies mixing between roll and pitch for helis
|
AP_Int16 heli_phase_angle; // 0 to 360 degrees. specifies mixing between roll and pitch for helis
|
||||||
AP_Float heli_collective_yaw_effect; // -5.0 ~ 5.0. Feed forward control from collective to yaw. 1.0 = move rudder right 1% for every 1% of collective above the mid point
|
AP_Float heli_collective_yaw_effect; // -5.0 ~ 5.0. Feed forward control from collective to yaw. 1.0 = move rudder right 1% for every 1% of collective above the mid point
|
||||||
|
AP_Int8 heli_h1_swash_enabled; // 0 = CCPM swashplate, 1 = H1 swashplate (no servo mixing)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// RC channels
|
// RC channels
|
||||||
|
@ -387,20 +389,21 @@ public:
|
||||||
auto_slew_rate (AUTO_SLEW_RATE),
|
auto_slew_rate (AUTO_SLEW_RATE),
|
||||||
|
|
||||||
#if FRAME_CONFIG == HELI_FRAME
|
#if FRAME_CONFIG == HELI_FRAME
|
||||||
heli_servo1_pos (-60),
|
heli_servo1_pos (-60),
|
||||||
heli_servo2_pos (60),
|
heli_servo2_pos (60),
|
||||||
heli_servo3_pos (180),
|
heli_servo3_pos (180),
|
||||||
heli_roll_max (4500),
|
heli_roll_max (4500),
|
||||||
heli_pitch_max (4500),
|
heli_pitch_max (4500),
|
||||||
heli_collective_min (1250),
|
heli_collective_min (1250),
|
||||||
heli_collective_max (1750),
|
heli_collective_max (1750),
|
||||||
heli_collective_mid (1500),
|
heli_collective_mid (1500),
|
||||||
heli_ext_gyro_enabled (0),
|
heli_ext_gyro_enabled (0),
|
||||||
heli_ext_gyro_gain (1350),
|
heli_ext_gyro_gain (1350),
|
||||||
heli_servo_averaging (0),
|
heli_servo_averaging (0),
|
||||||
heli_servo_manual (0),
|
heli_servo_manual (0),
|
||||||
heli_phase_angle (0),
|
heli_phase_angle (0),
|
||||||
heli_collective_yaw_effect (0),
|
heli_collective_yaw_effect (0),
|
||||||
|
heli_h1_swash_enabled (0),
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
rc_speed(RC_FAST_SPEED),
|
rc_speed(RC_FAST_SPEED),
|
||||||
|
|
|
@ -76,16 +76,17 @@ static const AP_Param::Info var_info[] PROGMEM = {
|
||||||
GGROUP(heli_servo_2, "HS2_", RC_Channel),
|
GGROUP(heli_servo_2, "HS2_", RC_Channel),
|
||||||
GGROUP(heli_servo_3, "HS3_", RC_Channel),
|
GGROUP(heli_servo_3, "HS3_", RC_Channel),
|
||||||
GGROUP(heli_servo_4, "HS4_", RC_Channel),
|
GGROUP(heli_servo_4, "HS4_", RC_Channel),
|
||||||
GSCALAR(heli_servo1_pos, "SV1_POS_"),
|
GSCALAR(heli_servo1_pos, "SV1_POS"),
|
||||||
GSCALAR(heli_servo2_pos, "SV2_POS_"),
|
GSCALAR(heli_servo2_pos, "SV2_POS"),
|
||||||
GSCALAR(heli_servo3_pos, "SV3_POS_"),
|
GSCALAR(heli_servo3_pos, "SV3_POS"),
|
||||||
GSCALAR(heli_roll_max, "ROL_MAX_"),
|
GSCALAR(heli_roll_max, "ROL_MAX"),
|
||||||
GSCALAR(heli_pitch_max, "PIT_MAX_"),
|
GSCALAR(heli_pitch_max, "PIT_MAX"),
|
||||||
GSCALAR(heli_collective_min, "COL_MIN_"),
|
GSCALAR(heli_collective_min, "COL_MIN"),
|
||||||
GSCALAR(heli_collective_max, "COL_MAX_"),
|
GSCALAR(heli_collective_max, "COL_MAX"),
|
||||||
GSCALAR(heli_collective_mid, "COL_MID_"),
|
GSCALAR(heli_collective_mid, "COL_MID"),
|
||||||
GSCALAR(heli_ext_gyro_enabled, "GYR_ENABLE_"),
|
GSCALAR(heli_ext_gyro_enabled, "GYR_ENABLE"),
|
||||||
GSCALAR(heli_ext_gyro_gain, "GYR_GAIN_"),
|
GSCALAR(heli_h1_swash_enabled, "H1_ENABLE"),
|
||||||
|
GSCALAR(heli_ext_gyro_gain, "GYR_GAIN"),
|
||||||
GSCALAR(heli_servo_averaging, "SV_AVG"),
|
GSCALAR(heli_servo_averaging, "SV_AVG"),
|
||||||
GSCALAR(heli_servo_manual, "HSV_MAN"),
|
GSCALAR(heli_servo_manual, "HSV_MAN"),
|
||||||
GSCALAR(heli_phase_angle, "H_PHANG"),
|
GSCALAR(heli_phase_angle, "H_PHANG"),
|
||||||
|
|
|
@ -107,7 +107,7 @@
|
||||||
|
|
||||||
// default RC speed in Hz if INSTANT_PWM is not used
|
// default RC speed in Hz if INSTANT_PWM is not used
|
||||||
#ifndef RC_FAST_SPEED
|
#ifndef RC_FAST_SPEED
|
||||||
# define RC_FAST_SPEED 400
|
# define RC_FAST_SPEED 490
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// LED and IO Pins
|
// LED and IO Pins
|
||||||
|
@ -425,6 +425,10 @@
|
||||||
# define GROUND_START_DELAY 3
|
# define GROUND_START_DELAY 3
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#ifndef AUTOMATIC_DECLINATION
|
||||||
|
#define AUTOMATIC_DECLINATION DISABLED
|
||||||
|
#endif
|
||||||
|
|
||||||
|
|
||||||
//////////////////////////////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////////////////////////////
|
||||||
//////////////////////////////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////////////////////////////
|
||||||
|
@ -578,7 +582,7 @@
|
||||||
# define STABILIZE_ROLL_P 4.5
|
# define STABILIZE_ROLL_P 4.5
|
||||||
#endif
|
#endif
|
||||||
#ifndef STABILIZE_ROLL_I
|
#ifndef STABILIZE_ROLL_I
|
||||||
# define STABILIZE_ROLL_I 0.0
|
# define STABILIZE_ROLL_I 0.1
|
||||||
#endif
|
#endif
|
||||||
#ifndef STABILIZE_ROLL_IMAX
|
#ifndef STABILIZE_ROLL_IMAX
|
||||||
# define STABILIZE_ROLL_IMAX 40 // degrees
|
# define STABILIZE_ROLL_IMAX 40 // degrees
|
||||||
|
@ -588,7 +592,7 @@
|
||||||
# define STABILIZE_PITCH_P 4.5
|
# define STABILIZE_PITCH_P 4.5
|
||||||
#endif
|
#endif
|
||||||
#ifndef STABILIZE_PITCH_I
|
#ifndef STABILIZE_PITCH_I
|
||||||
# define STABILIZE_PITCH_I 0.0
|
# define STABILIZE_PITCH_I 0.1
|
||||||
#endif
|
#endif
|
||||||
#ifndef STABILIZE_PITCH_IMAX
|
#ifndef STABILIZE_PITCH_IMAX
|
||||||
# define STABILIZE_PITCH_IMAX 40 // degrees
|
# define STABILIZE_PITCH_IMAX 40 // degrees
|
||||||
|
@ -615,7 +619,7 @@
|
||||||
# define RATE_ROLL_I 0.0
|
# define RATE_ROLL_I 0.0
|
||||||
#endif
|
#endif
|
||||||
#ifndef RATE_ROLL_D
|
#ifndef RATE_ROLL_D
|
||||||
# define RATE_ROLL_D 0.002
|
# define RATE_ROLL_D 0.000 //.002
|
||||||
#endif
|
#endif
|
||||||
#ifndef RATE_ROLL_IMAX
|
#ifndef RATE_ROLL_IMAX
|
||||||
# define RATE_ROLL_IMAX 5 // degrees
|
# define RATE_ROLL_IMAX 5 // degrees
|
||||||
|
@ -628,7 +632,7 @@
|
||||||
# define RATE_PITCH_I 0.0
|
# define RATE_PITCH_I 0.0
|
||||||
#endif
|
#endif
|
||||||
#ifndef RATE_PITCH_D
|
#ifndef RATE_PITCH_D
|
||||||
# define RATE_PITCH_D 0.002
|
# define RATE_PITCH_D 0.00
|
||||||
#endif
|
#endif
|
||||||
#ifndef RATE_PITCH_IMAX
|
#ifndef RATE_PITCH_IMAX
|
||||||
# define RATE_PITCH_IMAX 5 // degrees
|
# define RATE_PITCH_IMAX 5 // degrees
|
||||||
|
@ -641,7 +645,7 @@
|
||||||
# define RATE_YAW_I 0.0
|
# define RATE_YAW_I 0.0
|
||||||
#endif
|
#endif
|
||||||
#ifndef RATE_YAW_D
|
#ifndef RATE_YAW_D
|
||||||
# define RATE_YAW_D .000
|
# define RATE_YAW_D 0.000
|
||||||
#endif
|
#endif
|
||||||
#ifndef RATE_YAW_IMAX
|
#ifndef RATE_YAW_IMAX
|
||||||
# define RATE_YAW_IMAX 50 // degrees
|
# define RATE_YAW_IMAX 50 // degrees
|
||||||
|
@ -649,18 +653,18 @@
|
||||||
|
|
||||||
|
|
||||||
#ifndef STABILIZE_D
|
#ifndef STABILIZE_D
|
||||||
# define STABILIZE_D 0.1
|
# define STABILIZE_D 0.15
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifndef STABILIZE_D_SCHEDULE
|
#ifndef STABILIZE_D_SCHEDULE
|
||||||
# define STABILIZE_D_SCHEDULE 0.0
|
# define STABILIZE_D_SCHEDULE 0.5
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
//////////////////////////////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////////////////////////////
|
||||||
// Loiter control gains
|
// Loiter control gains
|
||||||
//
|
//
|
||||||
#ifndef LOITER_P
|
#ifndef LOITER_P
|
||||||
# define LOITER_P .8
|
# define LOITER_P .4
|
||||||
#endif
|
#endif
|
||||||
#ifndef LOITER_I
|
#ifndef LOITER_I
|
||||||
# define LOITER_I 0.0
|
# define LOITER_I 0.0
|
||||||
|
@ -672,15 +676,11 @@
|
||||||
//////////////////////////////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////////////////////////////
|
||||||
// Loiter Navigation control gains
|
// Loiter Navigation control gains
|
||||||
//
|
//
|
||||||
#ifndef LOITER_RATE
|
|
||||||
# define LOITER_RATE 1
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifndef LOITER_RATE_P
|
#ifndef LOITER_RATE_P
|
||||||
# define LOITER_RATE_P 3.5 //
|
# define LOITER_RATE_P 2.0 //
|
||||||
#endif
|
#endif
|
||||||
#ifndef LOITER_RATE_I
|
#ifndef LOITER_RATE_I
|
||||||
# define LOITER_RATE_I 0.2 // Wind control
|
# define LOITER_RATE_I 0.10 // Wind control
|
||||||
#endif
|
#endif
|
||||||
#ifndef LOITER_RATE_D
|
#ifndef LOITER_RATE_D
|
||||||
# define LOITER_RATE_D 0.0 // try 2 or 3 for LOITER_RATE 1
|
# define LOITER_RATE_D 0.0 // try 2 or 3 for LOITER_RATE 1
|
||||||
|
@ -693,10 +693,10 @@
|
||||||
// WP Navigation control gains
|
// WP Navigation control gains
|
||||||
//
|
//
|
||||||
#ifndef NAV_P
|
#ifndef NAV_P
|
||||||
# define NAV_P 3.5 //
|
# define NAV_P 3.0 //
|
||||||
#endif
|
#endif
|
||||||
#ifndef NAV_I
|
#ifndef NAV_I
|
||||||
# define NAV_I 0.2 // Wind control
|
# define NAV_I 0.20 // Wind control
|
||||||
#endif
|
#endif
|
||||||
#ifndef NAV_D
|
#ifndef NAV_D
|
||||||
# define NAV_D 0.00 //
|
# define NAV_D 0.00 //
|
||||||
|
@ -727,10 +727,10 @@
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifndef ALT_HOLD_P
|
#ifndef ALT_HOLD_P
|
||||||
# define ALT_HOLD_P 0.4 //
|
# define ALT_HOLD_P 0.5 //
|
||||||
#endif
|
#endif
|
||||||
#ifndef ALT_HOLD_I
|
#ifndef ALT_HOLD_I
|
||||||
# define ALT_HOLD_I 0.04
|
# define ALT_HOLD_I 0.015
|
||||||
#endif
|
#endif
|
||||||
#ifndef ALT_HOLD_IMAX
|
#ifndef ALT_HOLD_IMAX
|
||||||
# define ALT_HOLD_IMAX 300
|
# define ALT_HOLD_IMAX 300
|
||||||
|
@ -738,10 +738,10 @@
|
||||||
|
|
||||||
// RATE control
|
// RATE control
|
||||||
#ifndef THROTTLE_P
|
#ifndef THROTTLE_P
|
||||||
# define THROTTLE_P 0.35 //
|
# define THROTTLE_P 0.25 //
|
||||||
#endif
|
#endif
|
||||||
#ifndef THROTTLE_I
|
#ifndef THROTTLE_I
|
||||||
# define THROTTLE_I 0.0 //
|
# define THROTTLE_I 0.0 // Don't edit
|
||||||
#endif
|
#endif
|
||||||
#ifndef THROTTLE_D
|
#ifndef THROTTLE_D
|
||||||
# define THROTTLE_D 0.02 //
|
# define THROTTLE_D 0.02 //
|
||||||
|
@ -939,5 +939,9 @@
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
||||||
|
// experimental quaternion code
|
||||||
|
#ifndef QUATERNION_ENABLE
|
||||||
|
# define QUATERNION_ENABLE DISABLED
|
||||||
|
#endif
|
||||||
|
|
||||||
#endif // __ARDUCOPTER_CONFIG_H__
|
#endif // __ARDUCOPTER_CONFIG_H__
|
||||||
|
|
|
@ -72,13 +72,6 @@ static void read_trim_switch()
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
#elif CH7_OPTION == CH7_ADC_FILTER
|
|
||||||
if (g.rc_7.radio_in > CH_7_PWM_TRIGGER){
|
|
||||||
adc.filter_result = true;
|
|
||||||
}else{
|
|
||||||
adc.filter_result = false;
|
|
||||||
}
|
|
||||||
|
|
||||||
#elif CH7_OPTION == CH7_AUTO_TRIM
|
#elif CH7_OPTION == CH7_AUTO_TRIM
|
||||||
if (g.rc_7.radio_in > CH_7_PWM_TRIGGER){
|
if (g.rc_7.radio_in > CH_7_PWM_TRIGGER){
|
||||||
auto_level_counter = 10;
|
auto_level_counter = 10;
|
||||||
|
@ -186,9 +179,6 @@ static void auto_trim()
|
||||||
|
|
||||||
//Serial.println("Done");
|
//Serial.println("Done");
|
||||||
auto_level_counter = 0;
|
auto_level_counter = 0;
|
||||||
|
|
||||||
// set TC
|
|
||||||
init_throttle_cruise();
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
|
@ -7,6 +7,9 @@
|
||||||
#define ENABLED 1
|
#define ENABLED 1
|
||||||
#define DISABLED 0
|
#define DISABLED 0
|
||||||
|
|
||||||
|
// this avoids a very common config error
|
||||||
|
#define ENABLE ENABLED
|
||||||
|
#define DISABLE DISABLED
|
||||||
|
|
||||||
// Flight modes
|
// Flight modes
|
||||||
// ------------
|
// ------------
|
||||||
|
@ -125,8 +128,6 @@
|
||||||
#define OF_LOITER 10 // Hold a single location using optical flow sensor
|
#define OF_LOITER 10 // Hold a single location using optical flow sensor
|
||||||
#define NUM_MODES 11
|
#define NUM_MODES 11
|
||||||
|
|
||||||
#define INITIALISING 9 // in startup routines
|
|
||||||
|
|
||||||
#define SIMPLE_1 1
|
#define SIMPLE_1 1
|
||||||
#define SIMPLE_2 2
|
#define SIMPLE_2 2
|
||||||
#define SIMPLE_3 4
|
#define SIMPLE_3 4
|
||||||
|
@ -169,6 +170,7 @@
|
||||||
|
|
||||||
#define CH6_NAV_I 20
|
#define CH6_NAV_I 20
|
||||||
#define CH6_LOITER_RATE_P 22
|
#define CH6_LOITER_RATE_P 22
|
||||||
|
#define CH6_LOITER_RATE_D 23
|
||||||
|
|
||||||
|
|
||||||
// nav byte mask
|
// nav byte mask
|
||||||
|
@ -234,6 +236,9 @@ enum ap_message {
|
||||||
MSG_NEXT_WAYPOINT,
|
MSG_NEXT_WAYPOINT,
|
||||||
MSG_NEXT_PARAM,
|
MSG_NEXT_PARAM,
|
||||||
MSG_STATUSTEXT,
|
MSG_STATUSTEXT,
|
||||||
|
MSG_DCM,
|
||||||
|
MSG_SIMSTATE,
|
||||||
|
MSG_HWSTATUS,
|
||||||
MSG_RETRY_DEFERRED // this must be last
|
MSG_RETRY_DEFERRED // this must be last
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
|
@ -28,15 +28,40 @@ static void heli_reset_swash()
|
||||||
g.heli_servo_3.radio_min = 1000;
|
g.heli_servo_3.radio_min = 1000;
|
||||||
g.heli_servo_3.radio_max = 2000;
|
g.heli_servo_3.radio_max = 2000;
|
||||||
|
|
||||||
// pitch factors
|
if (!g.heli_h1_swash_enabled){ //CCPM Swashplate, perform servo control mixing
|
||||||
heli_pitchFactor[CH_1] = cos(radians(g.heli_servo1_pos - g.heli_phase_angle));
|
|
||||||
heli_pitchFactor[CH_2] = cos(radians(g.heli_servo2_pos - g.heli_phase_angle));
|
// roll factors
|
||||||
heli_pitchFactor[CH_3] = cos(radians(g.heli_servo3_pos - g.heli_phase_angle));
|
heli_rollFactor[CH_1] = cos(radians(g.heli_servo1_pos + 90 - g.heli_phase_angle));
|
||||||
|
heli_rollFactor[CH_2] = cos(radians(g.heli_servo2_pos + 90 - g.heli_phase_angle));
|
||||||
|
heli_rollFactor[CH_3] = cos(radians(g.heli_servo3_pos + 90 - g.heli_phase_angle));
|
||||||
|
|
||||||
|
// pitch factors
|
||||||
|
heli_pitchFactor[CH_1] = cos(radians(g.heli_servo1_pos - g.heli_phase_angle));
|
||||||
|
heli_pitchFactor[CH_2] = cos(radians(g.heli_servo2_pos - g.heli_phase_angle));
|
||||||
|
heli_pitchFactor[CH_3] = cos(radians(g.heli_servo3_pos - g.heli_phase_angle));
|
||||||
|
|
||||||
|
// collective factors
|
||||||
|
heli_collectiveFactor[CH_1] = 1;
|
||||||
|
heli_collectiveFactor[CH_2] = 1;
|
||||||
|
heli_collectiveFactor[CH_3] = 1;
|
||||||
|
|
||||||
|
}else{ //H1 Swashplate, keep servo outputs seperated
|
||||||
|
|
||||||
// roll factors
|
// roll factors
|
||||||
heli_rollFactor[CH_1] = cos(radians(g.heli_servo1_pos + 90 - g.heli_phase_angle));
|
heli_rollFactor[CH_1] = 1;
|
||||||
heli_rollFactor[CH_2] = cos(radians(g.heli_servo2_pos + 90 - g.heli_phase_angle));
|
heli_rollFactor[CH_2] = 0;
|
||||||
heli_rollFactor[CH_3] = cos(radians(g.heli_servo3_pos + 90 - g.heli_phase_angle));
|
heli_rollFactor[CH_3] = 0;
|
||||||
|
|
||||||
|
// pitch factors
|
||||||
|
heli_pitchFactor[CH_1] = 0;
|
||||||
|
heli_pitchFactor[CH_2] = 1;
|
||||||
|
heli_pitchFactor[CH_3] = 0;
|
||||||
|
|
||||||
|
// collective factors
|
||||||
|
heli_collectiveFactor[CH_1] = 0;
|
||||||
|
heli_collectiveFactor[CH_2] = 0;
|
||||||
|
heli_collectiveFactor[CH_3] = 1;
|
||||||
|
}
|
||||||
|
|
||||||
// set throttle scaling
|
// set throttle scaling
|
||||||
heli_collective_scalar = ((float)(g.rc_3.radio_max - g.rc_3.radio_min))/1000.0;
|
heli_collective_scalar = ((float)(g.rc_3.radio_max - g.rc_3.radio_min))/1000.0;
|
||||||
|
@ -69,15 +94,40 @@ static void heli_init_swash()
|
||||||
// determine scalar throttle input
|
// determine scalar throttle input
|
||||||
heli_collective_scalar = ((float)(g.heli_collective_max-g.heli_collective_min))/1000.0;
|
heli_collective_scalar = ((float)(g.heli_collective_max-g.heli_collective_min))/1000.0;
|
||||||
|
|
||||||
// pitch factors
|
if (!g.heli_h1_swash_enabled){ //CCPM Swashplate, perform control mixing
|
||||||
heli_pitchFactor[CH_1] = cos(radians(g.heli_servo1_pos - g.heli_phase_angle));
|
|
||||||
heli_pitchFactor[CH_2] = cos(radians(g.heli_servo2_pos - g.heli_phase_angle));
|
// roll factors
|
||||||
heli_pitchFactor[CH_3] = cos(radians(g.heli_servo3_pos - g.heli_phase_angle));
|
heli_rollFactor[CH_1] = cos(radians(g.heli_servo1_pos + 90 - g.heli_phase_angle));
|
||||||
|
heli_rollFactor[CH_2] = cos(radians(g.heli_servo2_pos + 90 - g.heli_phase_angle));
|
||||||
|
heli_rollFactor[CH_3] = cos(radians(g.heli_servo3_pos + 90 - g.heli_phase_angle));
|
||||||
|
|
||||||
|
// pitch factors
|
||||||
|
heli_pitchFactor[CH_1] = cos(radians(g.heli_servo1_pos - g.heli_phase_angle));
|
||||||
|
heli_pitchFactor[CH_2] = cos(radians(g.heli_servo2_pos - g.heli_phase_angle));
|
||||||
|
heli_pitchFactor[CH_3] = cos(radians(g.heli_servo3_pos - g.heli_phase_angle));
|
||||||
|
|
||||||
|
// collective factors
|
||||||
|
heli_collectiveFactor[CH_1] = 1;
|
||||||
|
heli_collectiveFactor[CH_2] = 1;
|
||||||
|
heli_collectiveFactor[CH_3] = 1;
|
||||||
|
|
||||||
|
}else{ //H1 Swashplate, keep servo outputs seperated
|
||||||
|
|
||||||
// roll factors
|
// roll factors
|
||||||
heli_rollFactor[CH_1] = cos(radians(g.heli_servo1_pos + 90 - g.heli_phase_angle));
|
heli_rollFactor[CH_1] = 1;
|
||||||
heli_rollFactor[CH_2] = cos(radians(g.heli_servo2_pos + 90 - g.heli_phase_angle));
|
heli_rollFactor[CH_2] = 0;
|
||||||
heli_rollFactor[CH_3] = cos(radians(g.heli_servo3_pos + 90 - g.heli_phase_angle));
|
heli_rollFactor[CH_3] = 0;
|
||||||
|
|
||||||
|
// pitch factors
|
||||||
|
heli_pitchFactor[CH_1] = 0;
|
||||||
|
heli_pitchFactor[CH_2] = 1;
|
||||||
|
heli_pitchFactor[CH_3] = 0;
|
||||||
|
|
||||||
|
// collective factors
|
||||||
|
heli_collectiveFactor[CH_1] = 0;
|
||||||
|
heli_collectiveFactor[CH_2] = 0;
|
||||||
|
heli_collectiveFactor[CH_3] = 1;
|
||||||
|
}
|
||||||
|
|
||||||
// servo min/max values
|
// servo min/max values
|
||||||
g.heli_servo_1.radio_min = 1000;
|
g.heli_servo_1.radio_min = 1000;
|
||||||
|
@ -160,9 +210,9 @@ static void heli_move_swash(int roll_out, int pitch_out, int coll_out, int yaw_o
|
||||||
}
|
}
|
||||||
|
|
||||||
// swashplate servos
|
// swashplate servos
|
||||||
g.heli_servo_1.servo_out = (heli_rollFactor[CH_1] * roll_out + heli_pitchFactor[CH_1] * pitch_out)/10 + coll_out_scaled + (g.heli_servo_1.radio_trim-1500);
|
g.heli_servo_1.servo_out = (heli_rollFactor[CH_1] * roll_out + heli_pitchFactor[CH_1] * pitch_out)/10 + heli_collectiveFactor[CH_1] * coll_out_scaled + (g.heli_servo_1.radio_trim-1500) + g.heli_h1_swash_enabled * 500;
|
||||||
g.heli_servo_2.servo_out = (heli_rollFactor[CH_2] * roll_out + heli_pitchFactor[CH_2] * pitch_out)/10 + coll_out_scaled + (g.heli_servo_2.radio_trim-1500);
|
g.heli_servo_2.servo_out = (heli_rollFactor[CH_2] * roll_out + heli_pitchFactor[CH_2] * pitch_out)/10 + heli_collectiveFactor[CH_2] * coll_out_scaled + (g.heli_servo_2.radio_trim-1500) + g.heli_h1_swash_enabled * 500;
|
||||||
g.heli_servo_3.servo_out = (heli_rollFactor[CH_3] * roll_out + heli_pitchFactor[CH_3] * pitch_out)/10 + coll_out_scaled + (g.heli_servo_3.radio_trim-1500);
|
g.heli_servo_3.servo_out = (heli_rollFactor[CH_3] * roll_out + heli_pitchFactor[CH_3] * pitch_out)/10 + heli_collectiveFactor[CH_3] * coll_out_scaled + (g.heli_servo_3.radio_trim-1500);
|
||||||
g.heli_servo_4.servo_out = yaw_out + yaw_offset;
|
g.heli_servo_4.servo_out = yaw_out + yaw_offset;
|
||||||
|
|
||||||
// use servo_out to calculate pwm_out and radio_out
|
// use servo_out to calculate pwm_out and radio_out
|
||||||
|
|
|
@ -77,9 +77,9 @@ static void output_motors_armed()
|
||||||
|
|
||||||
|
|
||||||
// Tridge's stability patch
|
// Tridge's stability patch
|
||||||
for (int m = 0; m <= 6; m++){
|
for (int m = 1; m <= 6; m++){
|
||||||
int c = ch_of_mot(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.
|
int c_opp = ch_of_mot(((m-1)^1)+1); // ((m-1)^1)+1 is the opposite motor. c_opp is channel of opposite motor.
|
||||||
if(motor_out[c] > out_max){
|
if(motor_out[c] > out_max){
|
||||||
motor_out[c_opp] -= motor_out[c] - out_max;
|
motor_out[c_opp] -= motor_out[c] - out_max;
|
||||||
motor_out[c] = out_max;
|
motor_out[c] = out_max;
|
||||||
|
@ -108,7 +108,7 @@ static void output_motors_armed()
|
||||||
|
|
||||||
// this filter slows the acceleration of motors vs the deceleration
|
// this filter slows the acceleration of motors vs the deceleration
|
||||||
// Idea by Denny Rowland to help with his Yaw issue
|
// Idea by Denny Rowland to help with his Yaw issue
|
||||||
for(int8_t m = 0; m <= 6; m++){
|
for(int8_t m = 1; m <= 6; m++){
|
||||||
int c = ch_of_mot(m);
|
int c = ch_of_mot(m);
|
||||||
if(motor_filtered[c] < motor_out[c]){
|
if(motor_filtered[c] < motor_out[c]){
|
||||||
motor_filtered[c] = (motor_out[c] + motor_filtered[c]) / 2;
|
motor_filtered[c] = (motor_out[c] + motor_filtered[c]) / 2;
|
||||||
|
|
|
@ -163,7 +163,7 @@ static void output_motors_armed()
|
||||||
|
|
||||||
// this filter slows the acceleration of motors vs the deceleration
|
// this filter slows the acceleration of motors vs the deceleration
|
||||||
// Idea by Denny Rowland to help with his Yaw issue
|
// Idea by Denny Rowland to help with his Yaw issue
|
||||||
for(int8_t m = 0; m <= 8; m++){
|
for(int8_t m = 1; m <= 8; m++){
|
||||||
int c = ch_of_mot(m);
|
int c = ch_of_mot(m);
|
||||||
if(motor_filtered[c] < motor_out[c]){
|
if(motor_filtered[c] < motor_out[c]){
|
||||||
motor_filtered[c] = (motor_out[c] + motor_filtered[c]) / 2;
|
motor_filtered[c] = (motor_out[c] + motor_filtered[c]) / 2;
|
||||||
|
|
|
@ -113,7 +113,7 @@ static void output_motors_armed()
|
||||||
|
|
||||||
// this filter slows the acceleration of motors vs the deceleration
|
// this filter slows the acceleration of motors vs the deceleration
|
||||||
// Idea by Denny Rowland to help with his Yaw issue
|
// Idea by Denny Rowland to help with his Yaw issue
|
||||||
for(int8_t m = 0; m <= 8; m++){
|
for(int8_t m = 1; m <= 8; m++){
|
||||||
int i = ch_of_mot(m);
|
int i = ch_of_mot(m);
|
||||||
if(motor_filtered[i] < motor_out[i]){
|
if(motor_filtered[i] < motor_out[i]){
|
||||||
motor_filtered[i] = (motor_out[i] + motor_filtered[i]) / 2;
|
motor_filtered[i] = (motor_out[i] + motor_filtered[i]) / 2;
|
||||||
|
|
|
@ -100,21 +100,11 @@ static void output_motors_armed()
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// this filter slows the acceleration of motors vs the deceleration
|
APM_RC.OutputCh(MOT_1, motor_out[MOT_1]);
|
||||||
// Idea by Denny Rowland to help with his Yaw issue
|
APM_RC.OutputCh(MOT_2, motor_out[MOT_2]);
|
||||||
for(int8_t i = MOT_1; i <= MOT_4; i++){
|
APM_RC.OutputCh(MOT_3, motor_out[MOT_3]);
|
||||||
if(motor_filtered[i] < motor_out[i]){
|
APM_RC.OutputCh(MOT_4, motor_out[MOT_4]);
|
||||||
motor_filtered[i] = (motor_out[i] + motor_filtered[i]) / 2;
|
|
||||||
}else{
|
|
||||||
// don't filter
|
|
||||||
motor_filtered[i] = motor_out[i];
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
APM_RC.OutputCh(MOT_1, motor_filtered[MOT_1]);
|
|
||||||
APM_RC.OutputCh(MOT_2, motor_filtered[MOT_2]);
|
|
||||||
APM_RC.OutputCh(MOT_3, motor_filtered[MOT_3]);
|
|
||||||
APM_RC.OutputCh(MOT_4, motor_filtered[MOT_4]);
|
|
||||||
|
|
||||||
#if INSTANT_PWM == 1
|
#if INSTANT_PWM == 1
|
||||||
// InstantPWM
|
// InstantPWM
|
||||||
|
|
|
@ -119,8 +119,8 @@ static void output_motors_armed()
|
||||||
|
|
||||||
// this filter slows the acceleration of motors vs the deceleration
|
// this filter slows the acceleration of motors vs the deceleration
|
||||||
// Idea by Denny Rowland to help with his Yaw issue
|
// Idea by Denny Rowland to help with his Yaw issue
|
||||||
for(int8_t m = 0; m <= 6; m++){
|
for(int8_t m = 1; m <= 6; m++){
|
||||||
int i = ch_of_mot(m);
|
int i = ch_of_mot(m);
|
||||||
if(motor_filtered[i] < motor_out[i]){
|
if(motor_filtered[i] < motor_out[i]){
|
||||||
motor_filtered[i] = (motor_out[i] + motor_filtered[i]) / 2;
|
motor_filtered[i] = (motor_out[i] + motor_filtered[i]) / 2;
|
||||||
}else{
|
}else{
|
||||||
|
|
|
@ -55,11 +55,11 @@ static void calc_XY_velocity(){
|
||||||
|
|
||||||
// straightforward approach:
|
// straightforward approach:
|
||||||
///*
|
///*
|
||||||
x_actual_speed = x_speed_old + (float)(g_gps->longitude - last_longitude) * scaleLongDown * tmp;
|
x_actual_speed = x_speed_old + (float)(g_gps->longitude - last_longitude) * scaleLongDown * tmp;
|
||||||
y_actual_speed = y_speed_old + (float)(g_gps->latitude - last_latitude) * tmp;
|
y_actual_speed = y_speed_old + (float)(g_gps->latitude - last_latitude) * tmp;
|
||||||
|
|
||||||
x_actual_speed = x_actual_speed >> 1;
|
x_actual_speed = x_actual_speed >> 1;
|
||||||
y_actual_speed = y_actual_speed >> 1;
|
y_actual_speed = y_actual_speed >> 1;
|
||||||
|
|
||||||
x_speed_old = x_actual_speed;
|
x_speed_old = x_actual_speed;
|
||||||
y_speed_old = y_actual_speed;
|
y_speed_old = y_actual_speed;
|
||||||
|
@ -82,6 +82,12 @@ static void calc_XY_velocity(){
|
||||||
|
|
||||||
static void calc_location_error(struct Location *next_loc)
|
static void calc_location_error(struct Location *next_loc)
|
||||||
{
|
{
|
||||||
|
static int16_t last_lon_error = 0;
|
||||||
|
static int16_t last_lat_error = 0;
|
||||||
|
|
||||||
|
static int16_t last_lon_d = 0;
|
||||||
|
static int16_t last_lat_d = 0;
|
||||||
|
|
||||||
/*
|
/*
|
||||||
Becuase we are using lat and lon to do our distance errors here's a quick chart:
|
Becuase we are using lat and lon to do our distance errors here's a quick chart:
|
||||||
100 = 1m
|
100 = 1m
|
||||||
|
@ -96,44 +102,55 @@ static void calc_location_error(struct Location *next_loc)
|
||||||
|
|
||||||
// Y Error
|
// Y Error
|
||||||
lat_error = next_loc->lat - current_loc.lat; // 500 - 0 = 500 Go North
|
lat_error = next_loc->lat - current_loc.lat; // 500 - 0 = 500 Go North
|
||||||
|
|
||||||
|
int16_t tmp;
|
||||||
|
|
||||||
|
tmp = (long_error - last_lon_error);
|
||||||
|
if(abs(abs(tmp) -last_lon_d) > 15) tmp = x_rate_d;
|
||||||
|
x_rate_d = lon_rate_d_filter.apply(tmp);
|
||||||
|
last_lon_d = abs(tmp);
|
||||||
|
|
||||||
|
tmp = (lat_error - last_lat_error);
|
||||||
|
if(abs(abs(tmp) -last_lat_d) > 15) tmp = y_rate_d;
|
||||||
|
//if(abs(tmp) > 80) tmp = y_rate_d;
|
||||||
|
y_rate_d = lat_rate_d_filter.apply(tmp);
|
||||||
|
last_lat_d = abs(tmp);
|
||||||
|
|
||||||
|
int16_t t22 = x_rate_d * (g.pid_loiter_rate_lon.kD() / dTnav);
|
||||||
|
int16_t raww = (long_error - last_lon_error);
|
||||||
|
|
||||||
|
//Serial.printf("XX, %d, %d, %d\n", raww, x_rate_d, t22);
|
||||||
|
|
||||||
|
last_lon_error = long_error;
|
||||||
|
last_lat_error = lat_error;
|
||||||
}
|
}
|
||||||
|
|
||||||
#define NAV_ERR_MAX 600
|
#define NAV_ERR_MAX 600
|
||||||
static void calc_loiter(int x_error, int y_error)
|
static void calc_loiter(int x_error, int y_error)
|
||||||
{
|
{
|
||||||
#if LOITER_RATE == 1
|
|
||||||
int16_t x_target_speed, y_target_speed;
|
int16_t x_target_speed, y_target_speed;
|
||||||
int16_t x_iterm, y_iterm;
|
//int16_t x_iterm, y_iterm;
|
||||||
|
|
||||||
// East / West
|
// East / West
|
||||||
x_target_speed = g.pi_loiter_lon.get_p(x_error); // not contstrained yet
|
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_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
|
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 = g.pid_loiter_rate_lon.get_pi(x_rate_error, dTnav);
|
||||||
|
nav_lon += x_rate_d * (g.pid_loiter_rate_lon.kD() / dTnav);
|
||||||
nav_lon = constrain(nav_lon, -3000, 3000); // 30°
|
nav_lon = constrain(nav_lon, -3000, 3000); // 30°
|
||||||
|
|
||||||
// North / South
|
// North / South
|
||||||
y_target_speed = g.pi_loiter_lat.get_p(y_error);
|
y_target_speed = g.pi_loiter_lat.get_p(y_error);
|
||||||
//y_target_speed = constrain(y_target_speed, -250, 250);
|
//y_target_speed = constrain(y_target_speed, -250, 250);
|
||||||
y_rate_error = y_target_speed - y_actual_speed;
|
y_rate_error = y_target_speed - y_actual_speed;
|
||||||
nav_lat = g.pid_loiter_rate_lat.get_pid(y_rate_error, dTnav);
|
nav_lat = g.pid_loiter_rate_lat.get_pi(y_rate_error, dTnav);
|
||||||
|
nav_lat += y_rate_d * (g.pid_loiter_rate_lat.kD() / dTnav);
|
||||||
nav_lat = constrain(nav_lat, -3000, 3000); // 30°
|
nav_lat = constrain(nav_lat, -3000, 3000); // 30°
|
||||||
|
|
||||||
// copy over I term to Nav_Rate
|
// copy over I term to Nav_Rate
|
||||||
g.pid_nav_lon.set_integrator(g.pid_loiter_rate_lon.get_integrator());
|
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());
|
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,
|
// Wind I term based on location error,
|
||||||
// limit windup
|
// limit windup
|
||||||
|
@ -347,16 +364,21 @@ static void clear_new_altitude()
|
||||||
alt_change_flag = REACHED_ALT;
|
alt_change_flag = REACHED_ALT;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
static void force_new_altitude(int32_t _new_alt)
|
||||||
|
{
|
||||||
|
next_WP.alt = _new_alt;
|
||||||
|
target_altitude = _new_alt;
|
||||||
|
alt_change_flag = REACHED_ALT;
|
||||||
|
}
|
||||||
|
|
||||||
static void set_new_altitude(int32_t _new_alt)
|
static void set_new_altitude(int32_t _new_alt)
|
||||||
{
|
{
|
||||||
if(_new_alt == current_loc.alt){
|
if(_new_alt == current_loc.alt){
|
||||||
next_WP.alt = _new_alt;
|
force_new_altitude(_new_alt);
|
||||||
target_altitude = _new_alt;
|
|
||||||
alt_change_flag = REACHED_ALT;
|
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
// just to be clear
|
// We start at the current location altitude and gradually change alt
|
||||||
next_WP.alt = current_loc.alt;
|
next_WP.alt = current_loc.alt;
|
||||||
|
|
||||||
// for calculating the delta time
|
// for calculating the delta time
|
||||||
|
@ -419,14 +441,16 @@ static int32_t get_new_altitude()
|
||||||
}
|
}
|
||||||
|
|
||||||
int32_t diff = abs(next_WP.alt - target_altitude);
|
int32_t diff = abs(next_WP.alt - target_altitude);
|
||||||
|
// scale is how we generate a desired rate from the elapsed time
|
||||||
|
// a smaller scale means faster rates
|
||||||
int8_t _scale = 4;
|
int8_t _scale = 4;
|
||||||
|
|
||||||
if (next_WP.alt < target_altitude){
|
if (next_WP.alt < target_altitude){
|
||||||
// we are below the target alt
|
// we are below the target alt
|
||||||
if(diff < 200){
|
if(diff < 200){
|
||||||
_scale = 5;
|
|
||||||
} else {
|
|
||||||
_scale = 4;
|
_scale = 4;
|
||||||
|
} else {
|
||||||
|
_scale = 3;
|
||||||
}
|
}
|
||||||
}else {
|
}else {
|
||||||
// we are above the target, going down
|
// we are above the target, going down
|
||||||
|
|
|
@ -35,7 +35,7 @@ static void init_barometer(void)
|
||||||
//Serial.printf("init %ld, %d, -, %ld, %ld\n", barometer.RawTemp, barometer.Temp, barometer.RawPress, barometer.Press);
|
//Serial.printf("init %ld, %d, -, %ld, %ld\n", barometer.RawTemp, barometer.Temp, barometer.RawPress, barometer.Press);
|
||||||
}
|
}
|
||||||
|
|
||||||
for(i = 0; i < 20; i++){
|
for(i = 0; i < 40; i++){
|
||||||
delay(20);
|
delay(20);
|
||||||
|
|
||||||
#if HIL_MODE == HIL_MODE_SENSORS
|
#if HIL_MODE == HIL_MODE_SENSORS
|
||||||
|
@ -44,15 +44,25 @@ static void init_barometer(void)
|
||||||
|
|
||||||
// Get initial data from absolute pressure sensor
|
// Get initial data from absolute pressure sensor
|
||||||
barometer.read();
|
barometer.read();
|
||||||
ground_pressure = barometer.get_pressure();
|
ground_pressure = baro_filter.apply(barometer.get_pressure());
|
||||||
ground_temperature = (ground_temperature * 7 + barometer.get_temperature()) / 8;
|
|
||||||
//Serial.printf("init %ld, %d, -, %ld, %ld, -, %d, %ld\n", barometer.RawTemp, barometer.Temp, barometer.RawPress, barometer.Press, ground_temperature, ground_pressure);
|
//Serial.printf("t: %ld, p: %d\n", ground_pressure, ground_temperature);
|
||||||
|
|
||||||
|
/*Serial.printf("init %d, %d, -, %d, %d, -, %d, %d\n",
|
||||||
|
barometer.RawTemp,
|
||||||
|
barometer.Temp,
|
||||||
|
barometer.RawPress,
|
||||||
|
barometer.Press,
|
||||||
|
ground_temperature,
|
||||||
|
ground_pressure);*/
|
||||||
}
|
}
|
||||||
|
// save our ground temp
|
||||||
|
ground_temperature = barometer.get_temperature();
|
||||||
}
|
}
|
||||||
|
|
||||||
static void reset_baro(void)
|
static void reset_baro(void)
|
||||||
{
|
{
|
||||||
ground_pressure = barometer.get_pressure();
|
ground_pressure = baro_filter.apply(barometer.get_pressure());
|
||||||
ground_temperature = barometer.get_temperature();
|
ground_temperature = barometer.get_temperature();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -61,7 +71,7 @@ static int32_t read_barometer(void)
|
||||||
float x, scaling, temp;
|
float x, scaling, temp;
|
||||||
|
|
||||||
barometer.read();
|
barometer.read();
|
||||||
float abs_pressure = barometer.get_pressure();
|
float abs_pressure = baro_filter.apply(barometer.get_pressure());
|
||||||
|
|
||||||
|
|
||||||
//Serial.printf("%ld, %ld, %ld, %ld\n", barometer.RawTemp, barometer.RawPress, barometer.Press, abs_pressure);
|
//Serial.printf("%ld, %ld, %ld, %ld\n", barometer.RawTemp, barometer.RawPress, barometer.Press, abs_pressure);
|
||||||
|
@ -84,7 +94,6 @@ static void init_compass()
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
dcm.set_compass(&compass);
|
dcm.set_compass(&compass);
|
||||||
compass.get_offsets(); // load offsets to account for airframe magnetic interference
|
|
||||||
compass.null_offsets_enable();
|
compass.null_offsets_enable();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -1162,6 +1162,9 @@ static void report_gps()
|
||||||
static void report_version()
|
static void report_version()
|
||||||
{
|
{
|
||||||
Serial.printf_P(PSTR("FW Ver: %d\n"),(int)g.format_version.get());
|
Serial.printf_P(PSTR("FW Ver: %d\n"),(int)g.format_version.get());
|
||||||
|
#if QUATERNION_ENABLE == ENABLED
|
||||||
|
Serial.printf_P(PSTR("Quaternion test\n"));
|
||||||
|
#endif
|
||||||
print_divider();
|
print_divider();
|
||||||
print_blanks(2);
|
print_blanks(2);
|
||||||
}
|
}
|
||||||
|
|
|
@ -218,7 +218,6 @@ static void init_ardupilot()
|
||||||
#if HIL_MODE != HIL_MODE_ATTITUDE
|
#if HIL_MODE != HIL_MODE_ATTITUDE
|
||||||
#if CONFIG_ADC == ENABLED
|
#if CONFIG_ADC == ENABLED
|
||||||
// begin filtering the ADC Gyros
|
// begin filtering the ADC Gyros
|
||||||
adc.filter_result = true;
|
|
||||||
adc.Init(&timer_scheduler); // APM ADC library initialization
|
adc.Init(&timer_scheduler); // APM ADC library initialization
|
||||||
#endif // CONFIG_ADC
|
#endif // CONFIG_ADC
|
||||||
|
|
||||||
|
@ -308,14 +307,6 @@ static void init_ardupilot()
|
||||||
// ---------------------------
|
// ---------------------------
|
||||||
reset_control_switch();
|
reset_control_switch();
|
||||||
|
|
||||||
#if HIL_MODE != HIL_MODE_ATTITUDE
|
|
||||||
dcm.kp_roll_pitch(0.130000);
|
|
||||||
dcm.ki_roll_pitch(0.00001278), // 50 hz I term
|
|
||||||
dcm.kp_yaw(0.08);
|
|
||||||
dcm.ki_yaw(0.00004);
|
|
||||||
dcm._clamp = 5;
|
|
||||||
#endif
|
|
||||||
|
|
||||||
// init the Z damopener
|
// init the Z damopener
|
||||||
// --------------------
|
// --------------------
|
||||||
#if ACCEL_ALT_HOLD != 0
|
#if ACCEL_ALT_HOLD != 0
|
||||||
|
@ -456,7 +447,7 @@ static void set_mode(byte mode)
|
||||||
roll_pitch_mode = ALT_HOLD_RP;
|
roll_pitch_mode = ALT_HOLD_RP;
|
||||||
throttle_mode = ALT_HOLD_THR;
|
throttle_mode = ALT_HOLD_THR;
|
||||||
|
|
||||||
set_next_WP(¤t_loc);
|
force_new_altitude(max(current_loc.alt, 100));
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case AUTO:
|
case AUTO:
|
||||||
|
@ -532,16 +523,8 @@ static void set_mode(byte mode)
|
||||||
motor_auto_armed = true;
|
motor_auto_armed = true;
|
||||||
}
|
}
|
||||||
|
|
||||||
if(throttle_mode == THROTTLE_MANUAL){
|
// called to calculate gain for alt hold
|
||||||
// reset all of the throttle iterms
|
update_throttle_cruise();
|
||||||
update_throttle_cruise();
|
|
||||||
|
|
||||||
// reset auto_throttle
|
|
||||||
nav_throttle = 0;
|
|
||||||
}else {
|
|
||||||
// an automatic throttle
|
|
||||||
init_throttle_cruise();
|
|
||||||
}
|
|
||||||
|
|
||||||
if(roll_pitch_mode <= ROLL_PITCH_ACRO){
|
if(roll_pitch_mode <= ROLL_PITCH_ACRO){
|
||||||
// We are under manual attitude control
|
// We are under manual attitude control
|
||||||
|
@ -594,18 +577,10 @@ static void update_throttle_cruise()
|
||||||
g.throttle_cruise += tmp;
|
g.throttle_cruise += tmp;
|
||||||
reset_throttle_I();
|
reset_throttle_I();
|
||||||
}
|
}
|
||||||
}
|
|
||||||
|
|
||||||
static void
|
// recalc kp
|
||||||
init_throttle_cruise()
|
//g.pid_throttle.kP((float)g.throttle_cruise.get() / 981.0);
|
||||||
{
|
//Serial.printf("kp:%1.4f\n",kp);
|
||||||
#if AUTO_THROTTLE_HOLD == 0
|
|
||||||
// are we moving from manual throttle to auto_throttle?
|
|
||||||
if((old_control_mode <= STABILIZE) && (g.rc_3.control_in > MINIMUM_THROTTLE)){
|
|
||||||
reset_throttle_I();
|
|
||||||
g.throttle_cruise.set_and_save(g.rc_3.control_in);
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
}
|
}
|
||||||
|
|
||||||
#if CLI_SLIDER_ENABLED == ENABLED && CLI_ENABLED == ENABLED
|
#if CLI_SLIDER_ENABLED == ENABLED && CLI_ENABLED == ENABLED
|
||||||
|
@ -675,7 +650,6 @@ void flash_leds(bool on)
|
||||||
*/
|
*/
|
||||||
uint16_t board_voltage(void)
|
uint16_t board_voltage(void)
|
||||||
{
|
{
|
||||||
static uint16_t vcc = 5000;
|
|
||||||
const uint8_t mux = (_BV(REFS0)|_BV(MUX4)|_BV(MUX3)|_BV(MUX2)|_BV(MUX1));
|
const uint8_t mux = (_BV(REFS0)|_BV(MUX4)|_BV(MUX3)|_BV(MUX2)|_BV(MUX1));
|
||||||
|
|
||||||
if (ADMUX == mux) {
|
if (ADMUX == mux) {
|
||||||
|
@ -685,14 +659,17 @@ uint16_t board_voltage(void)
|
||||||
counter--;
|
counter--;
|
||||||
if (counter == 0) {
|
if (counter == 0) {
|
||||||
// we don't actually expect this timeout to happen,
|
// we don't actually expect this timeout to happen,
|
||||||
// but we don't want any more code that could hang
|
// but we don't want any more code that could hang. We
|
||||||
return vcc;
|
// report 0V so it is clear in the logs that we don't know
|
||||||
|
// the value
|
||||||
|
return 0;
|
||||||
}
|
}
|
||||||
uint32_t result = ADCL | ADCH<<8;
|
uint32_t result = ADCL | ADCH<<8;
|
||||||
vcc = 1126400L / result; // Read and back-calculate Vcc in mV
|
return 1126400UL / result; // Read and back-calculate Vcc in mV
|
||||||
} else {
|
}
|
||||||
ADMUX = mux; // switch mux, settle time is needed
|
// switch mux, settle time is needed. We don't want to delay
|
||||||
}
|
// waiting for the settle, so report 0 as a "don't know" value
|
||||||
return vcc; // in mV
|
ADMUX = mux;
|
||||||
|
return 0; // we don't know the current voltage
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -329,9 +329,10 @@ test_radio(uint8_t argc, const Menu::arg *argv)
|
||||||
if(g.compass_enabled){
|
if(g.compass_enabled){
|
||||||
medium_loopCounter++;
|
medium_loopCounter++;
|
||||||
if(medium_loopCounter == 5){
|
if(medium_loopCounter == 5){
|
||||||
|
Matrix3f m = dcm.get_dcm_matrix();
|
||||||
compass.read(); // Read magnetometer
|
compass.read(); // Read magnetometer
|
||||||
compass.calculate(dcm.roll, dcm.pitch); // Calculate heading
|
compass.calculate(m);
|
||||||
compass.null_offsets(dcm.get_dcm_matrix());
|
compass.null_offsets(m);
|
||||||
medium_loopCounter = 0;
|
medium_loopCounter = 0;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -548,7 +549,9 @@ test_imu(uint8_t argc, const Menu::arg *argv)
|
||||||
|
|
||||||
if(g.compass_enabled){
|
if(g.compass_enabled){
|
||||||
compass.read(); // Read magnetometer
|
compass.read(); // Read magnetometer
|
||||||
compass.calculate(dcm.get_dcm_matrix());
|
Matrix3f m = dcm.get_dcm_matrix();
|
||||||
|
compass.calculate(m);
|
||||||
|
compass.null_offsets(m);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
fast_loopTimer = millis();
|
fast_loopTimer = millis();
|
||||||
|
|
|
@ -39,3 +39,6 @@
|
||||||
#define AIRSPEED_CRUISE 25
|
#define AIRSPEED_CRUISE 25
|
||||||
#define THROTTLE_FAILSAFE ENABLED
|
#define THROTTLE_FAILSAFE ENABLED
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
// Enabling this will use the GPS lat/long coordinate to get the compass declination
|
||||||
|
//#define AUTOMATIC_DECLINATION ENABLED
|
||||||
|
|
|
@ -41,6 +41,7 @@ version 2.1 of the License, or (at your option) any later version.
|
||||||
#include <AP_InertialSensor.h> // Inertial Sensor (uncalibated IMU) Library
|
#include <AP_InertialSensor.h> // Inertial Sensor (uncalibated IMU) Library
|
||||||
#include <AP_IMU.h> // ArduPilot Mega IMU Library
|
#include <AP_IMU.h> // ArduPilot Mega IMU Library
|
||||||
#include <AP_DCM.h> // ArduPilot Mega DCM Library
|
#include <AP_DCM.h> // ArduPilot Mega DCM Library
|
||||||
|
#include <AP_Quaternion.h> // Madgwick quaternion system
|
||||||
#include <PID.h> // PID library
|
#include <PID.h> // PID library
|
||||||
#include <RC_Channel.h> // RC Channel Library
|
#include <RC_Channel.h> // RC Channel Library
|
||||||
#include <AP_RangeFinder.h> // Range finder library
|
#include <AP_RangeFinder.h> // Range finder library
|
||||||
|
@ -59,6 +60,11 @@ version 2.1 of the License, or (at your option) any later version.
|
||||||
#include "Parameters.h"
|
#include "Parameters.h"
|
||||||
#include "GCS.h"
|
#include "GCS.h"
|
||||||
|
|
||||||
|
#if AUTOMATIC_DECLINATION == ENABLED
|
||||||
|
// this is in an #if to avoid the static data
|
||||||
|
#include <AP_Declination.h> // ArduPilot Mega Declination Helper Library
|
||||||
|
#endif
|
||||||
|
|
||||||
////////////////////////////////////////////////////////////////////////////////
|
////////////////////////////////////////////////////////////////////////////////
|
||||||
// Serial ports
|
// Serial ports
|
||||||
////////////////////////////////////////////////////////////////////////////////
|
////////////////////////////////////////////////////////////////////////////////
|
||||||
|
@ -186,7 +192,15 @@ AP_GPS_None g_gps_driver(NULL);
|
||||||
AP_InertialSensor_Oilpan ins( &adc );
|
AP_InertialSensor_Oilpan ins( &adc );
|
||||||
#endif // CONFIG_IMU_TYPE
|
#endif // CONFIG_IMU_TYPE
|
||||||
AP_IMU_INS imu( &ins );
|
AP_IMU_INS imu( &ins );
|
||||||
AP_DCM dcm(&imu, g_gps);
|
|
||||||
|
#if QUATERNION_ENABLE == ENABLED
|
||||||
|
// this shouldn't be called dcm of course, but until we
|
||||||
|
// decide to actually use something else, I don't want the patch
|
||||||
|
// size to be huge
|
||||||
|
AP_Quaternion dcm(&imu, g_gps);
|
||||||
|
#else
|
||||||
|
AP_DCM dcm(&imu, g_gps);
|
||||||
|
#endif
|
||||||
|
|
||||||
#elif HIL_MODE == HIL_MODE_SENSORS
|
#elif HIL_MODE == HIL_MODE_SENSORS
|
||||||
// sensor emulators
|
// sensor emulators
|
||||||
|
@ -709,7 +723,7 @@ static void fast_loop()
|
||||||
gcs_update();
|
gcs_update();
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
dcm.update_DCM();
|
dcm.update_DCM();
|
||||||
|
|
||||||
// uses the yaw from the DCM to give more accurate turns
|
// uses the yaw from the DCM to give more accurate turns
|
||||||
calc_bearing_error();
|
calc_bearing_error();
|
||||||
|
@ -771,8 +785,10 @@ static void medium_loop()
|
||||||
#if HIL_MODE != HIL_MODE_ATTITUDE
|
#if HIL_MODE != HIL_MODE_ATTITUDE
|
||||||
if (g.compass_enabled && compass.read()) {
|
if (g.compass_enabled && compass.read()) {
|
||||||
dcm.set_compass(&compass);
|
dcm.set_compass(&compass);
|
||||||
compass.calculate(dcm.get_dcm_matrix()); // Calculate heading
|
// Calculate heading
|
||||||
compass.null_offsets(dcm.get_dcm_matrix());
|
Matrix3f m = dcm.get_dcm_matrix();
|
||||||
|
compass.calculate(m);
|
||||||
|
compass.null_offsets(m);
|
||||||
} else {
|
} else {
|
||||||
dcm.set_compass(NULL);
|
dcm.set_compass(NULL);
|
||||||
}
|
}
|
||||||
|
@ -963,6 +979,12 @@ static void update_GPS(void)
|
||||||
init_home();
|
init_home();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#if AUTOMATIC_DECLINATION == ENABLED
|
||||||
|
if (g.compass_enabled) {
|
||||||
|
// Set compass declination automatically
|
||||||
|
compass.set_initial_location(g_gps->latitude, g_gps->longitude, false);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
ground_start_count = 0;
|
ground_start_count = 0;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
|
@ -485,8 +485,42 @@ static void NOINLINE send_raw_imu3(mavlink_channel_t chan)
|
||||||
imu.gx(), imu.gy(), imu.gz(),
|
imu.gx(), imu.gy(), imu.gz(),
|
||||||
imu.ax(), imu.ay(), imu.az());
|
imu.ax(), imu.ay(), imu.az());
|
||||||
}
|
}
|
||||||
|
|
||||||
|
static void NOINLINE send_dcm(mavlink_channel_t chan)
|
||||||
|
{
|
||||||
|
Vector3f omega_I = dcm.get_gyro_drift();
|
||||||
|
mavlink_msg_dcm_send(
|
||||||
|
chan,
|
||||||
|
omega_I.x,
|
||||||
|
omega_I.y,
|
||||||
|
omega_I.z,
|
||||||
|
dcm.get_accel_weight(),
|
||||||
|
dcm.get_renorm_val(),
|
||||||
|
dcm.get_error_rp(),
|
||||||
|
dcm.get_error_yaw());
|
||||||
|
}
|
||||||
|
|
||||||
#endif // HIL_MODE != HIL_MODE_ATTITUDE
|
#endif // HIL_MODE != HIL_MODE_ATTITUDE
|
||||||
|
|
||||||
|
#ifdef DESKTOP_BUILD
|
||||||
|
// report simulator state
|
||||||
|
static void NOINLINE send_simstate(mavlink_channel_t chan)
|
||||||
|
{
|
||||||
|
extern void sitl_simstate_send(uint8_t chan);
|
||||||
|
sitl_simstate_send((uint8_t)chan);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifndef DESKTOP_BUILD
|
||||||
|
static void NOINLINE send_hwstatus(mavlink_channel_t chan)
|
||||||
|
{
|
||||||
|
mavlink_msg_hwstatus_send(
|
||||||
|
chan,
|
||||||
|
board_voltage(),
|
||||||
|
I2c.lockup_count());
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
static void NOINLINE send_gps_status(mavlink_channel_t chan)
|
static void NOINLINE send_gps_status(mavlink_channel_t chan)
|
||||||
{
|
{
|
||||||
mavlink_msg_gps_status_send(
|
mavlink_msg_gps_status_send(
|
||||||
|
@ -645,6 +679,27 @@ static bool mavlink_try_send_message(mavlink_channel_t chan, enum ap_message id,
|
||||||
break;
|
break;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
case MSG_DCM:
|
||||||
|
#if HIL_MODE != HIL_MODE_ATTITUDE
|
||||||
|
CHECK_PAYLOAD_SIZE(DCM);
|
||||||
|
send_dcm(chan);
|
||||||
|
#endif
|
||||||
|
break;
|
||||||
|
|
||||||
|
case MSG_SIMSTATE:
|
||||||
|
#ifdef DESKTOP_BUILD
|
||||||
|
CHECK_PAYLOAD_SIZE(DCM);
|
||||||
|
send_simstate(chan);
|
||||||
|
#endif
|
||||||
|
break;
|
||||||
|
|
||||||
|
case MSG_HWSTATUS:
|
||||||
|
#ifndef DESKTOP_BUILD
|
||||||
|
CHECK_PAYLOAD_SIZE(HWSTATUS);
|
||||||
|
send_hwstatus(chan);
|
||||||
|
#endif
|
||||||
|
break;
|
||||||
|
|
||||||
case MSG_RETRY_DEFERRED:
|
case MSG_RETRY_DEFERRED:
|
||||||
break; // just here to prevent a warning
|
break; // just here to prevent a warning
|
||||||
}
|
}
|
||||||
|
@ -869,6 +924,7 @@ GCS_MAVLINK::data_stream_send(uint16_t freqMin, uint16_t freqMax)
|
||||||
|
|
||||||
if (freqLoopMatch(streamRateExtra1, freqMin, freqMax)){ // Use Extra 1 for AHRS info
|
if (freqLoopMatch(streamRateExtra1, freqMin, freqMax)){ // Use Extra 1 for AHRS info
|
||||||
send_message(MSG_ATTITUDE);
|
send_message(MSG_ATTITUDE);
|
||||||
|
send_message(MSG_SIMSTATE);
|
||||||
}
|
}
|
||||||
|
|
||||||
if (freqLoopMatch(streamRateExtra2, freqMin, freqMax)){ // Use Extra 2 for additional HIL info
|
if (freqLoopMatch(streamRateExtra2, freqMin, freqMax)){ // Use Extra 2 for additional HIL info
|
||||||
|
@ -876,7 +932,8 @@ GCS_MAVLINK::data_stream_send(uint16_t freqMin, uint16_t freqMax)
|
||||||
}
|
}
|
||||||
|
|
||||||
if (freqLoopMatch(streamRateExtra3, freqMin, freqMax)){
|
if (freqLoopMatch(streamRateExtra3, freqMin, freqMax)){
|
||||||
// Available datastream
|
send_message(MSG_DCM);
|
||||||
|
send_message(MSG_HWSTATUS);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
|
@ -245,9 +245,9 @@ static void Log_Write_Performance()
|
||||||
DataFlash.WriteByte(dcm.renorm_blowup_count);
|
DataFlash.WriteByte(dcm.renorm_blowup_count);
|
||||||
DataFlash.WriteByte(gps_fix_count);
|
DataFlash.WriteByte(gps_fix_count);
|
||||||
DataFlash.WriteInt((int)(dcm.get_health() * 1000));
|
DataFlash.WriteInt((int)(dcm.get_health() * 1000));
|
||||||
DataFlash.WriteInt((int)(dcm.get_integrator().x * 1000));
|
DataFlash.WriteInt((int)(dcm.get_gyro_drift().x * 1000));
|
||||||
DataFlash.WriteInt((int)(dcm.get_integrator().y * 1000));
|
DataFlash.WriteInt((int)(dcm.get_gyro_drift().y * 1000));
|
||||||
DataFlash.WriteInt((int)(dcm.get_integrator().z * 1000));
|
DataFlash.WriteInt((int)(dcm.get_gyro_drift().z * 1000));
|
||||||
DataFlash.WriteInt(pmTest1);
|
DataFlash.WriteInt(pmTest1);
|
||||||
DataFlash.WriteByte(END_BYTE);
|
DataFlash.WriteByte(END_BYTE);
|
||||||
}
|
}
|
||||||
|
|
|
@ -30,6 +30,9 @@ mavlink10:
|
||||||
sitl:
|
sitl:
|
||||||
make -f ../libraries/Desktop/Makefile.desktop
|
make -f ../libraries/Desktop/Makefile.desktop
|
||||||
|
|
||||||
|
sitl-quaternion:
|
||||||
|
make -f ../libraries/Desktop/Makefile.desktop EXTRAFLAGS="-DQUATERNION_ENABLE=ENABLED"
|
||||||
|
|
||||||
etags:
|
etags:
|
||||||
cd .. && etags -f ArduPlane/TAGS --langmap=C++:.pde.cpp.h $$(git ls-files ArduPlane libraries)
|
cd .. && etags -f ArduPlane/TAGS --langmap=C++:.pde.cpp.h $$(git ls-files ArduPlane libraries)
|
||||||
|
|
||||||
|
|
|
@ -36,6 +36,10 @@
|
||||||
#define ENABLED 1
|
#define ENABLED 1
|
||||||
#define DISABLED 0
|
#define DISABLED 0
|
||||||
|
|
||||||
|
// this avoids a very common config error
|
||||||
|
#define ENABLE ENABLED
|
||||||
|
#define DISABLE DISABLED
|
||||||
|
|
||||||
//////////////////////////////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////////////////////////////
|
||||||
//////////////////////////////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////////////////////////////
|
||||||
// HARDWARE CONFIGURATION AND CONNECTIONS
|
// HARDWARE CONFIGURATION AND CONNECTIONS
|
||||||
|
@ -414,6 +418,9 @@
|
||||||
# define GROUND_START_DELAY 0
|
# define GROUND_START_DELAY 0
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#ifndef AUTOMATIC_DECLINATION
|
||||||
|
#define AUTOMATIC_DECLINATION DISABLED
|
||||||
|
#endif
|
||||||
|
|
||||||
//////////////////////////////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////////////////////////////
|
||||||
// ENABLE_AIR_START
|
// ENABLE_AIR_START
|
||||||
|
@ -512,7 +519,7 @@
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
/* The following parmaeters have no corresponding control implementation
|
/* The following parameters have no corresponding control implementation
|
||||||
#ifndef THROTTLE_ALT_P
|
#ifndef THROTTLE_ALT_P
|
||||||
# define THROTTLE_ALT_P 0.32
|
# define THROTTLE_ALT_P 0.32
|
||||||
#endif
|
#endif
|
||||||
|
@ -833,3 +840,8 @@
|
||||||
#ifndef RESET_SWITCH_CHAN_PWM
|
#ifndef RESET_SWITCH_CHAN_PWM
|
||||||
# define RESET_SWITCH_CHAN_PWM 1750
|
# define RESET_SWITCH_CHAN_PWM 1750
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
// experimental quaternion code
|
||||||
|
#ifndef QUATERNION_ENABLE
|
||||||
|
# define QUATERNION_ENABLE DISABLED
|
||||||
|
#endif
|
||||||
|
|
|
@ -123,6 +123,9 @@ enum ap_message {
|
||||||
MSG_NEXT_PARAM,
|
MSG_NEXT_PARAM,
|
||||||
MSG_STATUSTEXT,
|
MSG_STATUSTEXT,
|
||||||
MSG_FENCE_STATUS,
|
MSG_FENCE_STATUS,
|
||||||
|
MSG_DCM,
|
||||||
|
MSG_SIMSTATE,
|
||||||
|
MSG_HWSTATUS,
|
||||||
MSG_RETRY_DEFERRED // this must be last
|
MSG_RETRY_DEFERRED // this must be last
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
|
@ -71,7 +71,10 @@ static void failsafe_short_off_event()
|
||||||
|
|
||||||
// re-read the switch so we can return to our preferred mode
|
// re-read the switch so we can return to our preferred mode
|
||||||
// --------------------------------------------------------
|
// --------------------------------------------------------
|
||||||
reset_control_switch();
|
if (control_mode == CIRCLE ||
|
||||||
|
(g.short_fs_action == 1 && control_mode == RTL)) {
|
||||||
|
reset_control_switch();
|
||||||
|
}
|
||||||
|
|
||||||
// Reset control integrators
|
// Reset control integrators
|
||||||
// ---------------------
|
// ---------------------
|
||||||
|
|
|
@ -103,6 +103,10 @@ static void init_ardupilot()
|
||||||
"\n\nFree RAM: %u\n"),
|
"\n\nFree RAM: %u\n"),
|
||||||
memcheck_available_memory());
|
memcheck_available_memory());
|
||||||
|
|
||||||
|
#if QUATERNION_ENABLE == ENABLED
|
||||||
|
Serial.printf_P(PSTR("Quaternion test\n"));
|
||||||
|
#endif
|
||||||
|
|
||||||
//
|
//
|
||||||
// Initialize Wire and SPI libraries
|
// Initialize Wire and SPI libraries
|
||||||
//
|
//
|
||||||
|
@ -577,7 +581,6 @@ void flash_leds(bool on)
|
||||||
*/
|
*/
|
||||||
uint16_t board_voltage(void)
|
uint16_t board_voltage(void)
|
||||||
{
|
{
|
||||||
static uint16_t vcc = 5000;
|
|
||||||
const uint8_t mux = (_BV(REFS0)|_BV(MUX4)|_BV(MUX3)|_BV(MUX2)|_BV(MUX1));
|
const uint8_t mux = (_BV(REFS0)|_BV(MUX4)|_BV(MUX3)|_BV(MUX2)|_BV(MUX1));
|
||||||
|
|
||||||
if (ADMUX == mux) {
|
if (ADMUX == mux) {
|
||||||
|
@ -587,14 +590,17 @@ uint16_t board_voltage(void)
|
||||||
counter--;
|
counter--;
|
||||||
if (counter == 0) {
|
if (counter == 0) {
|
||||||
// we don't actually expect this timeout to happen,
|
// we don't actually expect this timeout to happen,
|
||||||
// but we don't want any more code that could hang
|
// but we don't want any more code that could hang. We
|
||||||
return vcc;
|
// report 0V so it is clear in the logs that we don't know
|
||||||
|
// the value
|
||||||
|
return 0;
|
||||||
}
|
}
|
||||||
uint32_t result = ADCL | ADCH<<8;
|
uint32_t result = ADCL | ADCH<<8;
|
||||||
vcc = 1126400L / result; // Read and back-calculate Vcc in mV
|
return 1126400UL / result; // Read and back-calculate Vcc in mV
|
||||||
} else {
|
}
|
||||||
ADMUX = mux; // switch mux, settle time is needed
|
// switch mux, settle time is needed. We don't want to delay
|
||||||
}
|
// waiting for the settle, so report 0 as a "don't know" value
|
||||||
return vcc; // in mV
|
ADMUX = mux;
|
||||||
|
return 0; // we don't know the current voltage
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -534,7 +534,8 @@ test_imu(uint8_t argc, const Menu::arg *argv)
|
||||||
medium_loopCounter++;
|
medium_loopCounter++;
|
||||||
if(medium_loopCounter == 5){
|
if(medium_loopCounter == 5){
|
||||||
if (compass.read()) {
|
if (compass.read()) {
|
||||||
compass.calculate(dcm.get_dcm_matrix()); // Calculate heading
|
// Calculate heading
|
||||||
|
compass.calculate(dcm.get_dcm_matrix());
|
||||||
}
|
}
|
||||||
medium_loopCounter = 0;
|
medium_loopCounter = 0;
|
||||||
}
|
}
|
||||||
|
@ -599,8 +600,10 @@ test_mag(uint8_t argc, const Menu::arg *argv)
|
||||||
medium_loopCounter++;
|
medium_loopCounter++;
|
||||||
if(medium_loopCounter == 5){
|
if(medium_loopCounter == 5){
|
||||||
if (compass.read()) {
|
if (compass.read()) {
|
||||||
compass.calculate(dcm.get_dcm_matrix()); // Calculate heading
|
// Calculate heading
|
||||||
compass.null_offsets(dcm.get_dcm_matrix());
|
Matrix3f m = dcm.get_dcm_matrix();
|
||||||
|
compass.calculate(m);
|
||||||
|
compass.null_offsets(m);
|
||||||
}
|
}
|
||||||
medium_loopCounter = 0;
|
medium_loopCounter = 0;
|
||||||
}
|
}
|
||||||
|
|
|
@ -36,13 +36,13 @@ namespace ArdupilotMega.Antenna
|
||||||
|
|
||||||
if ((PanStartRange - PanEndRange) == 0)
|
if ((PanStartRange - PanEndRange) == 0)
|
||||||
{
|
{
|
||||||
System.Windows.Forms.MessageBox.Show("Invalid Pan Range", "Error");
|
System.Windows.Forms.CustomMessageBox.Show("Invalid Pan Range", "Error");
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
if ((TiltStartRange - TiltEndRange) == 0)
|
if ((TiltStartRange - TiltEndRange) == 0)
|
||||||
{
|
{
|
||||||
System.Windows.Forms.MessageBox.Show("Invalid Tilt Range", "Error");
|
System.Windows.Forms.CustomMessageBox.Show("Invalid Tilt Range", "Error");
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -50,7 +50,7 @@ namespace ArdupilotMega.Antenna
|
||||||
{
|
{
|
||||||
ComPort.Open();
|
ComPort.Open();
|
||||||
}
|
}
|
||||||
catch (Exception ex) { System.Windows.Forms.MessageBox.Show("Connect failed " + ex.Message,"Error"); return false; }
|
catch (Exception ex) { System.Windows.Forms.CustomMessageBox.Show("Connect failed " + ex.Message,"Error"); return false; }
|
||||||
|
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
|
@ -84,7 +84,7 @@
|
||||||
this.CMB_baudrate.Location = new System.Drawing.Point(337, 9);
|
this.CMB_baudrate.Location = new System.Drawing.Point(337, 9);
|
||||||
this.CMB_baudrate.Name = "CMB_baudrate";
|
this.CMB_baudrate.Name = "CMB_baudrate";
|
||||||
this.CMB_baudrate.Size = new System.Drawing.Size(121, 21);
|
this.CMB_baudrate.Size = new System.Drawing.Size(121, 21);
|
||||||
this.CMB_baudrate.TabIndex = 5;
|
this.CMB_baudrate.TabIndex = 2;
|
||||||
//
|
//
|
||||||
// CMB_serialport
|
// CMB_serialport
|
||||||
//
|
//
|
||||||
|
@ -93,14 +93,14 @@
|
||||||
this.CMB_serialport.Location = new System.Drawing.Point(210, 10);
|
this.CMB_serialport.Location = new System.Drawing.Point(210, 10);
|
||||||
this.CMB_serialport.Name = "CMB_serialport";
|
this.CMB_serialport.Name = "CMB_serialport";
|
||||||
this.CMB_serialport.Size = new System.Drawing.Size(121, 21);
|
this.CMB_serialport.Size = new System.Drawing.Size(121, 21);
|
||||||
this.CMB_serialport.TabIndex = 3;
|
this.CMB_serialport.TabIndex = 1;
|
||||||
//
|
//
|
||||||
// BUT_connect
|
// BUT_connect
|
||||||
//
|
//
|
||||||
this.BUT_connect.Location = new System.Drawing.Point(476, 9);
|
this.BUT_connect.Location = new System.Drawing.Point(476, 9);
|
||||||
this.BUT_connect.Name = "BUT_connect";
|
this.BUT_connect.Name = "BUT_connect";
|
||||||
this.BUT_connect.Size = new System.Drawing.Size(75, 23);
|
this.BUT_connect.Size = new System.Drawing.Size(75, 23);
|
||||||
this.BUT_connect.TabIndex = 4;
|
this.BUT_connect.TabIndex = 3;
|
||||||
this.BUT_connect.Text = "Connect";
|
this.BUT_connect.Text = "Connect";
|
||||||
this.BUT_connect.UseVisualStyleBackColor = true;
|
this.BUT_connect.UseVisualStyleBackColor = true;
|
||||||
this.BUT_connect.Click += new System.EventHandler(this.BUT_connect_Click);
|
this.BUT_connect.Click += new System.EventHandler(this.BUT_connect_Click);
|
||||||
|
@ -108,11 +108,12 @@
|
||||||
// TRK_pantrim
|
// TRK_pantrim
|
||||||
//
|
//
|
||||||
this.TRK_pantrim.Location = new System.Drawing.Point(153, 65);
|
this.TRK_pantrim.Location = new System.Drawing.Point(153, 65);
|
||||||
this.TRK_pantrim.Maximum = 180;
|
this.TRK_pantrim.Maximum = 90;
|
||||||
this.TRK_pantrim.Minimum = -180;
|
this.TRK_pantrim.Minimum = -90;
|
||||||
this.TRK_pantrim.Name = "TRK_pantrim";
|
this.TRK_pantrim.Name = "TRK_pantrim";
|
||||||
this.TRK_pantrim.Size = new System.Drawing.Size(375, 45);
|
this.TRK_pantrim.Size = new System.Drawing.Size(375, 45);
|
||||||
this.TRK_pantrim.TabIndex = 6;
|
this.TRK_pantrim.TabIndex = 5;
|
||||||
|
this.TRK_pantrim.TickFrequency = 5;
|
||||||
this.TRK_pantrim.Scroll += new System.EventHandler(this.TRK_pantrim_Scroll);
|
this.TRK_pantrim.Scroll += new System.EventHandler(this.TRK_pantrim_Scroll);
|
||||||
//
|
//
|
||||||
// TXT_panrange
|
// TXT_panrange
|
||||||
|
@ -120,17 +121,18 @@
|
||||||
this.TXT_panrange.Location = new System.Drawing.Point(83, 65);
|
this.TXT_panrange.Location = new System.Drawing.Point(83, 65);
|
||||||
this.TXT_panrange.Name = "TXT_panrange";
|
this.TXT_panrange.Name = "TXT_panrange";
|
||||||
this.TXT_panrange.Size = new System.Drawing.Size(64, 20);
|
this.TXT_panrange.Size = new System.Drawing.Size(64, 20);
|
||||||
this.TXT_panrange.TabIndex = 7;
|
this.TXT_panrange.TabIndex = 4;
|
||||||
this.TXT_panrange.Text = "180";
|
this.TXT_panrange.Text = "180";
|
||||||
|
this.TXT_panrange.TextChanged += new System.EventHandler(this.TXT_panrange_TextChanged);
|
||||||
//
|
//
|
||||||
// label3
|
// label3
|
||||||
//
|
//
|
||||||
this.label3.AutoSize = true;
|
this.label3.AutoSize = true;
|
||||||
this.label3.Location = new System.Drawing.Point(331, 49);
|
this.label3.Location = new System.Drawing.Point(326, 49);
|
||||||
this.label3.Name = "label3";
|
this.label3.Name = "label3";
|
||||||
this.label3.Size = new System.Drawing.Size(38, 13);
|
this.label3.Size = new System.Drawing.Size(27, 13);
|
||||||
this.label3.TabIndex = 10;
|
this.label3.TabIndex = 10;
|
||||||
this.label3.Text = "Center";
|
this.label3.Text = "Trim";
|
||||||
//
|
//
|
||||||
// label4
|
// label4
|
||||||
//
|
//
|
||||||
|
@ -153,29 +155,30 @@
|
||||||
// label6
|
// label6
|
||||||
//
|
//
|
||||||
this.label6.AutoSize = true;
|
this.label6.AutoSize = true;
|
||||||
this.label6.Location = new System.Drawing.Point(331, 125);
|
this.label6.Location = new System.Drawing.Point(326, 125);
|
||||||
this.label6.Name = "label6";
|
this.label6.Name = "label6";
|
||||||
this.label6.Size = new System.Drawing.Size(38, 13);
|
this.label6.Size = new System.Drawing.Size(27, 13);
|
||||||
this.label6.TabIndex = 16;
|
this.label6.TabIndex = 16;
|
||||||
this.label6.Text = "Center";
|
this.label6.Text = "Trim";
|
||||||
//
|
//
|
||||||
// TXT_tiltrange
|
// TXT_tiltrange
|
||||||
//
|
//
|
||||||
this.TXT_tiltrange.Location = new System.Drawing.Point(83, 141);
|
this.TXT_tiltrange.Location = new System.Drawing.Point(83, 141);
|
||||||
this.TXT_tiltrange.Name = "TXT_tiltrange";
|
this.TXT_tiltrange.Name = "TXT_tiltrange";
|
||||||
this.TXT_tiltrange.Size = new System.Drawing.Size(64, 20);
|
this.TXT_tiltrange.Size = new System.Drawing.Size(64, 20);
|
||||||
this.TXT_tiltrange.TabIndex = 13;
|
this.TXT_tiltrange.TabIndex = 6;
|
||||||
this.TXT_tiltrange.Text = "90";
|
this.TXT_tiltrange.Text = "90";
|
||||||
|
this.TXT_tiltrange.TextChanged += new System.EventHandler(this.TXT_tiltrange_TextChanged);
|
||||||
//
|
//
|
||||||
// TRK_tilttrim
|
// TRK_tilttrim
|
||||||
//
|
//
|
||||||
this.TRK_tilttrim.Location = new System.Drawing.Point(153, 141);
|
this.TRK_tilttrim.Location = new System.Drawing.Point(153, 141);
|
||||||
this.TRK_tilttrim.Maximum = 90;
|
this.TRK_tilttrim.Maximum = 45;
|
||||||
this.TRK_tilttrim.Minimum = -90;
|
this.TRK_tilttrim.Minimum = -45;
|
||||||
this.TRK_tilttrim.Name = "TRK_tilttrim";
|
this.TRK_tilttrim.Name = "TRK_tilttrim";
|
||||||
this.TRK_tilttrim.Size = new System.Drawing.Size(375, 45);
|
this.TRK_tilttrim.Size = new System.Drawing.Size(375, 45);
|
||||||
this.TRK_tilttrim.TabIndex = 12;
|
this.TRK_tilttrim.TabIndex = 7;
|
||||||
this.TRK_tilttrim.Value = 45;
|
this.TRK_tilttrim.TickFrequency = 5;
|
||||||
this.TRK_tilttrim.Scroll += new System.EventHandler(this.TRK_tilttrim_Scroll);
|
this.TRK_tilttrim.Scroll += new System.EventHandler(this.TRK_tilttrim_Scroll);
|
||||||
//
|
//
|
||||||
// label2
|
// label2
|
||||||
|
|
|
@ -19,7 +19,7 @@ namespace ArdupilotMega.Antenna
|
||||||
{
|
{
|
||||||
InitializeComponent();
|
InitializeComponent();
|
||||||
|
|
||||||
MainV2.fixtheme(this);
|
ThemeManager.ApplyThemeTo(this);
|
||||||
|
|
||||||
CMB_serialport.DataSource = SerialPort.GetPortNames();
|
CMB_serialport.DataSource = SerialPort.GetPortNames();
|
||||||
|
|
||||||
|
@ -54,7 +54,7 @@ namespace ArdupilotMega.Antenna
|
||||||
BaudRate = int.Parse(CMB_baudrate.Text)
|
BaudRate = int.Parse(CMB_baudrate.Text)
|
||||||
};
|
};
|
||||||
}
|
}
|
||||||
catch (Exception ex) { MessageBox.Show("Bad Port settings " + ex.Message); return; }
|
catch (Exception ex) { CustomMessageBox.Show("Bad Port settings " + ex.Message); return; }
|
||||||
|
|
||||||
try
|
try
|
||||||
{
|
{
|
||||||
|
@ -67,7 +67,7 @@ namespace ArdupilotMega.Antenna
|
||||||
tracker.TrimTilt = TRK_tilttrim.Value;
|
tracker.TrimTilt = TRK_tilttrim.Value;
|
||||||
|
|
||||||
}
|
}
|
||||||
catch (Exception ex) { MessageBox.Show("Bad User input " + ex.Message); return; }
|
catch (Exception ex) { CustomMessageBox.Show("Bad User input " + ex.Message); return; }
|
||||||
|
|
||||||
if (tracker.Init())
|
if (tracker.Init())
|
||||||
{
|
{
|
||||||
|
@ -111,5 +111,25 @@ namespace ArdupilotMega.Antenna
|
||||||
if (tracker != null)
|
if (tracker != null)
|
||||||
tracker.TrimTilt = TRK_tilttrim.Value;
|
tracker.TrimTilt = TRK_tilttrim.Value;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
private void TXT_panrange_TextChanged(object sender, EventArgs e)
|
||||||
|
{
|
||||||
|
int range;
|
||||||
|
|
||||||
|
int.TryParse(TXT_panrange.Text, out range);
|
||||||
|
|
||||||
|
TRK_pantrim.Minimum = range / 2 * -1;
|
||||||
|
TRK_pantrim.Maximum = range / 2;
|
||||||
|
}
|
||||||
|
|
||||||
|
private void TXT_tiltrange_TextChanged(object sender, EventArgs e)
|
||||||
|
{
|
||||||
|
int range;
|
||||||
|
|
||||||
|
int.TryParse(TXT_tiltrange.Text, out range);
|
||||||
|
|
||||||
|
TRK_tilttrim.Minimum = range / 2 * -1;
|
||||||
|
TRK_tilttrim.Maximum = range / 2;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
|
@ -178,7 +178,7 @@ namespace ArdupilotMega
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
if (DialogResult.Yes == MessageBox.Show("Is this a APM 2?", "APM 2", MessageBoxButtons.YesNo))
|
if (DialogResult.Yes == CustomMessageBox.Show("Is this a APM 2?", "APM 2", MessageBoxButtons.YesNo))
|
||||||
{
|
{
|
||||||
return "2560-2";
|
return "2560-2";
|
||||||
}
|
}
|
||||||
|
|
|
@ -86,7 +86,7 @@
|
||||||
<SignManifests>false</SignManifests>
|
<SignManifests>false</SignManifests>
|
||||||
</PropertyGroup>
|
</PropertyGroup>
|
||||||
<PropertyGroup>
|
<PropertyGroup>
|
||||||
<SignAssembly>true</SignAssembly>
|
<SignAssembly>false</SignAssembly>
|
||||||
</PropertyGroup>
|
</PropertyGroup>
|
||||||
<PropertyGroup />
|
<PropertyGroup />
|
||||||
<PropertyGroup>
|
<PropertyGroup>
|
||||||
|
@ -118,80 +118,66 @@
|
||||||
<ApplicationManifest>Properties\app.manifest</ApplicationManifest>
|
<ApplicationManifest>Properties\app.manifest</ApplicationManifest>
|
||||||
</PropertyGroup>
|
</PropertyGroup>
|
||||||
<ItemGroup>
|
<ItemGroup>
|
||||||
|
<Reference Include="alglibnet2, Version=0.0.0.0, Culture=neutral, processorArchitecture=MSIL">
|
||||||
|
<SpecificVersion>False</SpecificVersion>
|
||||||
|
</Reference>
|
||||||
<Reference Include="BSE.Windows.Forms">
|
<Reference Include="BSE.Windows.Forms">
|
||||||
<HintPath>..\..\..\..\..\Desktop\DIYDrones\myquad\greatmaps_e1bb830a18a3\Demo.WindowsForms\bin\Debug\BSE.Windows.Forms.dll</HintPath>
|
|
||||||
</Reference>
|
</Reference>
|
||||||
<Reference Include="Core">
|
<Reference Include="Core">
|
||||||
<HintPath>..\..\..\..\..\Desktop\DIYDrones\kml-library\KmlTestbed\bin\Release\Core.dll</HintPath>
|
|
||||||
</Reference>
|
</Reference>
|
||||||
<Reference Include="DirectShowLib-2005">
|
<Reference Include="DirectShowLib-2005">
|
||||||
<HintPath>..\..\..\..\..\Desktop\DIYDrones\myquad\DirectShowLib-2005.dll</HintPath>
|
|
||||||
</Reference>
|
</Reference>
|
||||||
<Reference Include="GMap.NET.Core">
|
<Reference Include="GMap.NET.Core">
|
||||||
<HintPath>..\..\..\..\..\Desktop\DIYDrones\myquad\greatmaps_e1bb830a18a3\GMap.NET.WindowsForms\bin\Debug\GMap.NET.Core.dll</HintPath>
|
|
||||||
</Reference>
|
</Reference>
|
||||||
<Reference Include="GMap.NET.WindowsForms">
|
<Reference Include="GMap.NET.WindowsForms">
|
||||||
<HintPath>..\..\..\..\..\Desktop\DIYDrones\myquad\greatmaps_e1bb830a18a3\GMap.NET.WindowsForms\bin\Debug\GMap.NET.WindowsForms.dll</HintPath>
|
|
||||||
</Reference>
|
</Reference>
|
||||||
<Reference Include="ICSharpCode.SharpZipLib">
|
<Reference Include="ICSharpCode.SharpZipLib">
|
||||||
<HintPath>..\..\..\..\..\Desktop\DIYDrones\SrcSamples\bin\ICSharpCode.SharpZipLib.dll</HintPath>
|
|
||||||
</Reference>
|
</Reference>
|
||||||
<Reference Include="IronPython, Version=2.7.0.40, Culture=neutral, PublicKeyToken=7f709c5b713576e1, processorArchitecture=MSIL">
|
<Reference Include="IronPython, Version=2.7.0.40, Culture=neutral, PublicKeyToken=7f709c5b713576e1, processorArchitecture=MSIL">
|
||||||
<SpecificVersion>False</SpecificVersion>
|
<SpecificVersion>False</SpecificVersion>
|
||||||
<HintPath>..\..\..\..\..\..\..\Program Files (x86)\IronPython 2.7.1\IronPython-2.6.1\IronPython.dll</HintPath>
|
|
||||||
</Reference>
|
</Reference>
|
||||||
<Reference Include="IronPython.Modules, Version=2.7.0.40, Culture=neutral, PublicKeyToken=7f709c5b713576e1, processorArchitecture=MSIL">
|
<Reference Include="IronPython.Modules, Version=2.7.0.40, Culture=neutral, PublicKeyToken=7f709c5b713576e1, processorArchitecture=MSIL">
|
||||||
<SpecificVersion>False</SpecificVersion>
|
<SpecificVersion>False</SpecificVersion>
|
||||||
<HintPath>..\..\..\..\..\..\..\Program Files (x86)\IronPython 2.7.1\IronPython-2.6.1\IronPython.Modules.dll</HintPath>
|
|
||||||
</Reference>
|
</Reference>
|
||||||
<Reference Include="KMLib">
|
<Reference Include="KMLib">
|
||||||
<HintPath>..\..\..\..\..\Desktop\DIYDrones\kml-library\KmlTestbed\bin\Release\KMLib.dll</HintPath>
|
|
||||||
</Reference>
|
</Reference>
|
||||||
<Reference Include="log4net, Version=1.2.11.0, Culture=neutral, PublicKeyToken=669e0ddf0bb1aa2a, processorArchitecture=MSIL">
|
<Reference Include="log4net, Version=1.2.11.0, Culture=neutral, PublicKeyToken=669e0ddf0bb1aa2a, processorArchitecture=MSIL">
|
||||||
<SpecificVersion>False</SpecificVersion>
|
<SpecificVersion>False</SpecificVersion>
|
||||||
<HintPath>Lib\log4net.dll</HintPath>
|
|
||||||
</Reference>
|
</Reference>
|
||||||
<Reference Include="MetaDataExtractor">
|
<Reference Include="MetaDataExtractor">
|
||||||
<HintPath>..\..\..\..\..\Desktop\DIYDrones\myquad\MetaDataExtractorCSharp240d\bin\Release\MetaDataExtractor.dll</HintPath>
|
|
||||||
</Reference>
|
</Reference>
|
||||||
<Reference Include="Microsoft.DirectX, Version=1.0.2902.0, Culture=neutral, PublicKeyToken=31bf3856ad364e35">
|
<Reference Include="Microsoft.DirectX, Version=1.0.2902.0, Culture=neutral, PublicKeyToken=31bf3856ad364e35">
|
||||||
<SpecificVersion>False</SpecificVersion>
|
<SpecificVersion>False</SpecificVersion>
|
||||||
<HintPath>..\..\..\..\..\..\..\Windows\Microsoft.NET\DirectX for Managed Code\1.0.2902.0\Microsoft.DirectX.dll</HintPath>
|
|
||||||
<Private>False</Private>
|
<Private>False</Private>
|
||||||
</Reference>
|
</Reference>
|
||||||
<Reference Include="Microsoft.DirectX.DirectInput, Version=1.0.2902.0, Culture=neutral, PublicKeyToken=31bf3856ad364e35">
|
<Reference Include="Microsoft.DirectX.DirectInput, Version=1.0.2902.0, Culture=neutral, PublicKeyToken=31bf3856ad364e35">
|
||||||
<SpecificVersion>False</SpecificVersion>
|
<SpecificVersion>False</SpecificVersion>
|
||||||
<HintPath>..\..\..\..\..\..\..\Windows\Microsoft.NET\DirectX for Managed Code\1.0.2902.0\Microsoft.DirectX.DirectInput.dll</HintPath>
|
|
||||||
<Private>False</Private>
|
<Private>False</Private>
|
||||||
</Reference>
|
</Reference>
|
||||||
<Reference Include="Microsoft.Dynamic">
|
<Reference Include="Microsoft.Dynamic">
|
||||||
<HintPath>..\..\..\..\..\..\..\Program Files (x86)\IronPython 2.7.1\IronPython-2.6.1\Microsoft.Dynamic.dll</HintPath>
|
|
||||||
</Reference>
|
</Reference>
|
||||||
<Reference Include="Microsoft.Scripting, Version=1.1.0.20, Culture=neutral, PublicKeyToken=7f709c5b713576e1, processorArchitecture=MSIL">
|
<Reference Include="Microsoft.Scripting, Version=1.1.0.20, Culture=neutral, PublicKeyToken=7f709c5b713576e1, processorArchitecture=MSIL">
|
||||||
<SpecificVersion>False</SpecificVersion>
|
<SpecificVersion>False</SpecificVersion>
|
||||||
<HintPath>..\..\..\..\..\..\..\Program Files (x86)\IronPython 2.7.1\IronPython-2.6.1\Microsoft.Scripting.dll</HintPath>
|
|
||||||
</Reference>
|
</Reference>
|
||||||
<Reference Include="Microsoft.Scripting.Core">
|
<Reference Include="Microsoft.Scripting.Core">
|
||||||
<HintPath>..\..\..\..\..\..\..\Program Files (x86)\IronPython 2.7.1\IronPython-2.6.1\Microsoft.Scripting.Core.dll</HintPath>
|
|
||||||
</Reference>
|
</Reference>
|
||||||
<Reference Include="Microsoft.Scripting.Debugging">
|
<Reference Include="Microsoft.Scripting.Debugging">
|
||||||
<HintPath>..\..\..\..\..\..\..\Program Files (x86)\IronPython 2.7.1\IronPython-2.6.1\Microsoft.Scripting.Debugging.dll</HintPath>
|
|
||||||
</Reference>
|
</Reference>
|
||||||
<Reference Include="Microsoft.Scripting.ExtensionAttribute, Version=2.0.0.0, Culture=neutral, PublicKeyToken=31bf3856ad364e35, processorArchitecture=MSIL">
|
<Reference Include="Microsoft.Scripting.ExtensionAttribute, Version=2.0.0.0, Culture=neutral, PublicKeyToken=31bf3856ad364e35, processorArchitecture=MSIL">
|
||||||
<SpecificVersion>False</SpecificVersion>
|
<SpecificVersion>False</SpecificVersion>
|
||||||
<HintPath>..\..\..\..\..\..\..\Program Files (x86)\IronPython 2.7.1\IronPython-2.6.1\Microsoft.Scripting.ExtensionAttribute.dll</HintPath>
|
</Reference>
|
||||||
|
<Reference Include="netDxf, Version=0.1.2.0, Culture=neutral, PublicKeyToken=1c75adeaa4c98f42, processorArchitecture=MSIL">
|
||||||
|
<SpecificVersion>False</SpecificVersion>
|
||||||
|
<HintPath>Lib\netDxf.dll</HintPath>
|
||||||
</Reference>
|
</Reference>
|
||||||
<Reference Include="OpenTK, Version=1.0.0.0, Culture=neutral, PublicKeyToken=bad199fe84eb3df4, processorArchitecture=MSIL">
|
<Reference Include="OpenTK, Version=1.0.0.0, Culture=neutral, PublicKeyToken=bad199fe84eb3df4, processorArchitecture=MSIL">
|
||||||
<SpecificVersion>False</SpecificVersion>
|
<SpecificVersion>False</SpecificVersion>
|
||||||
<HintPath>..\..\..\..\..\Desktop\DIYDrones\virtualglobebook-OpenGlobe-ddf1d7e\ThirdParty\OpenTKGL4\Binaries\OpenTK\Release\OpenTK.dll</HintPath>
|
|
||||||
</Reference>
|
</Reference>
|
||||||
<Reference Include="OpenTK.GLControl, Version=1.0.0.0, Culture=neutral, PublicKeyToken=bad199fe84eb3df4, processorArchitecture=MSIL">
|
<Reference Include="OpenTK.GLControl, Version=1.0.0.0, Culture=neutral, PublicKeyToken=bad199fe84eb3df4, processorArchitecture=MSIL">
|
||||||
<SpecificVersion>False</SpecificVersion>
|
<SpecificVersion>False</SpecificVersion>
|
||||||
<HintPath>..\..\..\..\..\Desktop\DIYDrones\opentk\trunk\Binaries\OpenTK\Release\OpenTK.GLControl.dll</HintPath>
|
|
||||||
</Reference>
|
</Reference>
|
||||||
<Reference Include="SharpKml, Version=1.1.0.0, Culture=neutral, PublicKeyToken=e608cd7d975805ad, processorArchitecture=MSIL">
|
<Reference Include="SharpKml, Version=1.1.0.0, Culture=neutral, PublicKeyToken=e608cd7d975805ad, processorArchitecture=MSIL">
|
||||||
<SpecificVersion>False</SpecificVersion>
|
<SpecificVersion>False</SpecificVersion>
|
||||||
<HintPath>..\..\..\..\..\Desktop\DIYDrones\myquad\sharpkml\SharpKml\bin\Release\SharpKml.dll</HintPath>
|
|
||||||
</Reference>
|
</Reference>
|
||||||
<Reference Include="System">
|
<Reference Include="System">
|
||||||
<Private>False</Private>
|
<Private>False</Private>
|
||||||
|
@ -203,7 +189,6 @@
|
||||||
<Private>False</Private>
|
<Private>False</Private>
|
||||||
</Reference>
|
</Reference>
|
||||||
<Reference Include="System.Data.SQLite">
|
<Reference Include="System.Data.SQLite">
|
||||||
<HintPath>..\..\..\..\..\Desktop\DIYDrones\myquad\greatmaps_e1bb830a18a3\Demo.WindowsForms\bin\Debug\x86\System.Data.SQLite.DLL</HintPath>
|
|
||||||
</Reference>
|
</Reference>
|
||||||
<Reference Include="System.Drawing">
|
<Reference Include="System.Drawing">
|
||||||
<Private>False</Private>
|
<Private>False</Private>
|
||||||
|
@ -225,7 +210,6 @@
|
||||||
</Reference>
|
</Reference>
|
||||||
<Reference Include="ZedGraph, Version=5.1.2.878, Culture=neutral, PublicKeyToken=02a83cbd123fcd60, processorArchitecture=MSIL">
|
<Reference Include="ZedGraph, Version=5.1.2.878, Culture=neutral, PublicKeyToken=02a83cbd123fcd60, processorArchitecture=MSIL">
|
||||||
<SpecificVersion>False</SpecificVersion>
|
<SpecificVersion>False</SpecificVersion>
|
||||||
<HintPath>..\..\ArdupilotSim\ArdupilotSim\bin\Release\ZedGraph.dll</HintPath>
|
|
||||||
</Reference>
|
</Reference>
|
||||||
</ItemGroup>
|
</ItemGroup>
|
||||||
<ItemGroup>
|
<ItemGroup>
|
||||||
|
@ -237,6 +221,8 @@
|
||||||
<Compile Include="Antenna\Tracker.Designer.cs">
|
<Compile Include="Antenna\Tracker.Designer.cs">
|
||||||
<DependentUpon>Tracker.cs</DependentUpon>
|
<DependentUpon>Tracker.cs</DependentUpon>
|
||||||
</Compile>
|
</Compile>
|
||||||
|
<Compile Include="CodeGen.cs" />
|
||||||
|
<Compile Include="Controls\CustomMessageBox.cs" />
|
||||||
<Compile Include="Controls\ProgressReporterDialogue.cs">
|
<Compile Include="Controls\ProgressReporterDialogue.cs">
|
||||||
<SubType>Form</SubType>
|
<SubType>Form</SubType>
|
||||||
</Compile>
|
</Compile>
|
||||||
|
@ -460,6 +446,8 @@
|
||||||
</Compile>
|
</Compile>
|
||||||
<Compile Include="Radio\Uploader.cs" />
|
<Compile Include="Radio\Uploader.cs" />
|
||||||
<Compile Include="LangUtility.cs" />
|
<Compile Include="LangUtility.cs" />
|
||||||
|
<Compile Include="test.cs" />
|
||||||
|
<Compile Include="ThemeManager.cs" />
|
||||||
<EmbeddedResource Include="Antenna\Tracker.resx">
|
<EmbeddedResource Include="Antenna\Tracker.resx">
|
||||||
<DependentUpon>Tracker.cs</DependentUpon>
|
<DependentUpon>Tracker.cs</DependentUpon>
|
||||||
</EmbeddedResource>
|
</EmbeddedResource>
|
||||||
|
|
|
@ -11,6 +11,6 @@
|
||||||
<UpdateUrlHistory />
|
<UpdateUrlHistory />
|
||||||
</PropertyGroup>
|
</PropertyGroup>
|
||||||
<PropertyGroup>
|
<PropertyGroup>
|
||||||
<ReferencePath>C:\Users\hog\Desktop\DIYDrones\myquad\greatmaps_e1bb830a18a3\Demo.WindowsForms\bin\Debug\;C:\Users\hog\Desktop\DIYDrones\myquad\sharpkml\SharpKml\bin\Release\;C:\Users\hog\Desktop\DIYDrones\myquad\MetaDataExtractorCSharp240d\bin\Release\;C:\Users\hog\Documents\Visual Studio 2010\Projects\ArdupilotMega\ArdupilotMega\Lib\</ReferencePath>
|
<ReferencePath>C:\Users\hog\Documents\Visual Studio 2010\Projects\ArdupilotMega\ArdupilotMega\Lib\;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>
|
||||||
</PropertyGroup>
|
</PropertyGroup>
|
||||||
</Project>
|
</Project>
|
|
@ -182,7 +182,7 @@ namespace ArdupilotMega
|
||||||
xmlwriter.Close();
|
xmlwriter.Close();
|
||||||
|
|
||||||
}
|
}
|
||||||
catch (Exception ex) { MessageBox.Show(ex.ToString()); }
|
catch (Exception ex) { CustomMessageBox.Show(ex.ToString()); }
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
|
@ -279,7 +279,7 @@ namespace ArdupilotMega
|
||||||
camera.sensorheight = float.Parse(TXT_sensheight.Text);
|
camera.sensorheight = float.Parse(TXT_sensheight.Text);
|
||||||
camera.sensorwidth = float.Parse(TXT_senswidth.Text);
|
camera.sensorwidth = float.Parse(TXT_senswidth.Text);
|
||||||
}
|
}
|
||||||
catch { MessageBox.Show("One of your entries is not a valid number"); return; }
|
catch { CustomMessageBox.Show("One of your entries is not a valid number"); return; }
|
||||||
|
|
||||||
cameras[CMB_camera.Text] = camera;
|
cameras[CMB_camera.Text] = camera;
|
||||||
|
|
||||||
|
|
|
@ -227,7 +227,7 @@ namespace WebCamService
|
||||||
camimage(image);
|
camimage(image);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
catch { Console.WriteLine("Grab bmp failed"); timer1.Enabled = false; this.CloseInterfaces(); System.Windows.Forms.MessageBox.Show("Problem with capture device, grabbing frame took longer than 5 sec"); }
|
catch { Console.WriteLine("Grab bmp failed"); timer1.Enabled = false; this.CloseInterfaces(); System.Windows.Forms.CustomMessageBox.Show("Problem with capture device, grabbing frame took longer than 5 sec"); }
|
||||||
}
|
}
|
||||||
|
|
||||||
/// <summary> build the capture graph for grabber. </summary>
|
/// <summary> build the capture graph for grabber. </summary>
|
||||||
|
|
|
@ -0,0 +1,339 @@
|
||||||
|
using System;
|
||||||
|
using System.Text;
|
||||||
|
using System.Drawing;
|
||||||
|
using System.Collections;
|
||||||
|
using System.ComponentModel;
|
||||||
|
using System.Windows.Forms;
|
||||||
|
using System.Data;
|
||||||
|
using System.CodeDom;
|
||||||
|
using Microsoft.CSharp;
|
||||||
|
using System.CodeDom.Compiler;
|
||||||
|
using System.Reflection;
|
||||||
|
using System.IO;
|
||||||
|
using System.Text.RegularExpressions;
|
||||||
|
|
||||||
|
namespace ArdupilotMega
|
||||||
|
{
|
||||||
|
static class CodeGen
|
||||||
|
{
|
||||||
|
public static string runCode(string code)
|
||||||
|
{
|
||||||
|
string answer = "";
|
||||||
|
|
||||||
|
GetMathMemberNames();
|
||||||
|
|
||||||
|
// change evaluation string to pick up Math class members
|
||||||
|
string expression = RefineEvaluationString(code);
|
||||||
|
|
||||||
|
// build the class using codedom
|
||||||
|
BuildClass(expression);
|
||||||
|
|
||||||
|
// compile the class into an in-memory assembly.
|
||||||
|
// if it doesn't compile, show errors in the window
|
||||||
|
CompilerResults results = CompileAssembly();
|
||||||
|
|
||||||
|
Console.WriteLine("...........................\r\n");
|
||||||
|
Console.WriteLine(_source.ToString());
|
||||||
|
|
||||||
|
// if the code compiled okay,
|
||||||
|
// run the code using the new assembly (which is inside the results)
|
||||||
|
if (results != null && results.CompiledAssembly != null)
|
||||||
|
{
|
||||||
|
// run the evaluation function
|
||||||
|
answer = RunCode(results);
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
}
|
||||||
|
|
||||||
|
return answer;
|
||||||
|
}
|
||||||
|
|
||||||
|
static ICodeCompiler CreateCompiler()
|
||||||
|
{
|
||||||
|
//Create an instance of the C# compiler
|
||||||
|
CodeDomProvider codeProvider = null;
|
||||||
|
codeProvider = new CSharpCodeProvider();
|
||||||
|
ICodeCompiler compiler = codeProvider.CreateCompiler();
|
||||||
|
return compiler;
|
||||||
|
}
|
||||||
|
|
||||||
|
/// <summary>
|
||||||
|
/// Creawte parameters for compiling
|
||||||
|
/// </summary>
|
||||||
|
/// <returns></returns>
|
||||||
|
static CompilerParameters CreateCompilerParameters()
|
||||||
|
{
|
||||||
|
//add compiler parameters and assembly references
|
||||||
|
CompilerParameters compilerParams = new CompilerParameters();
|
||||||
|
compilerParams.CompilerOptions = "/target:library /optimize";
|
||||||
|
compilerParams.GenerateExecutable = false;
|
||||||
|
compilerParams.GenerateInMemory = true;
|
||||||
|
compilerParams.IncludeDebugInformation = false;
|
||||||
|
compilerParams.ReferencedAssemblies.Add("mscorlib.dll");
|
||||||
|
compilerParams.ReferencedAssemblies.Add("System.dll");
|
||||||
|
compilerParams.ReferencedAssemblies.Add("System.Windows.Forms.dll");
|
||||||
|
|
||||||
|
//add any aditional references needed
|
||||||
|
// foreach (string refAssembly in code.References)
|
||||||
|
// compilerParams.ReferencedAssemblies.Add(refAssembly);
|
||||||
|
|
||||||
|
return compilerParams;
|
||||||
|
}
|
||||||
|
|
||||||
|
/// <summary>
|
||||||
|
/// Compiles the code from the code string
|
||||||
|
/// </summary>
|
||||||
|
/// <param name="compiler"></param>
|
||||||
|
/// <param name="parms"></param>
|
||||||
|
/// <param name="source"></param>
|
||||||
|
/// <returns></returns>
|
||||||
|
static private CompilerResults CompileCode(ICodeCompiler compiler, CompilerParameters parms, string source)
|
||||||
|
{
|
||||||
|
//actually compile the code
|
||||||
|
CompilerResults results = compiler.CompileAssemblyFromSource(
|
||||||
|
parms, source);
|
||||||
|
|
||||||
|
//Do we have any compiler errors?
|
||||||
|
if (results.Errors.Count > 0)
|
||||||
|
{
|
||||||
|
foreach (CompilerError error in results.Errors)
|
||||||
|
Console.WriteLine("Compile Error:" + error.ErrorText);
|
||||||
|
return null;
|
||||||
|
}
|
||||||
|
|
||||||
|
return results;
|
||||||
|
}
|
||||||
|
|
||||||
|
/// <summary>
|
||||||
|
/// Need to change eval string to use .NET Math library
|
||||||
|
/// </summary>
|
||||||
|
/// <param name="eval">evaluation expression</param>
|
||||||
|
/// <returns></returns>
|
||||||
|
static string RefineEvaluationString(string eval)
|
||||||
|
{
|
||||||
|
// look for regular expressions with only letters
|
||||||
|
Regex regularExpression = new Regex("[a-zA-Z_]+");
|
||||||
|
|
||||||
|
// track all functions and constants in the evaluation expression we already replaced
|
||||||
|
ArrayList replacelist = new ArrayList();
|
||||||
|
|
||||||
|
// find all alpha words inside the evaluation function that are possible functions
|
||||||
|
MatchCollection matches = regularExpression.Matches(eval);
|
||||||
|
foreach (Match m in matches)
|
||||||
|
{
|
||||||
|
// if the word is found in the math member map, add a Math prefix to it
|
||||||
|
bool isContainedInMathLibrary = _mathMembersMap[m.Value.ToUpper()] != null;
|
||||||
|
if (replacelist.Contains(m.Value) == false && isContainedInMathLibrary)
|
||||||
|
{
|
||||||
|
eval = eval.Replace(m.Value, "Math." + _mathMembersMap[m.Value.ToUpper()]);
|
||||||
|
}
|
||||||
|
|
||||||
|
// we matched it already, so don't allow us to replace it again
|
||||||
|
replacelist.Add(m.Value);
|
||||||
|
}
|
||||||
|
|
||||||
|
// return the modified evaluation string
|
||||||
|
return eval;
|
||||||
|
}
|
||||||
|
|
||||||
|
/// <summary>
|
||||||
|
/// Compiles the c# into an assembly if there are no syntax errors
|
||||||
|
/// </summary>
|
||||||
|
/// <returns></returns>
|
||||||
|
static private CompilerResults CompileAssembly()
|
||||||
|
{
|
||||||
|
// create a compiler
|
||||||
|
ICodeCompiler compiler = CreateCompiler();
|
||||||
|
// get all the compiler parameters
|
||||||
|
CompilerParameters parms = CreateCompilerParameters();
|
||||||
|
// compile the code into an assembly
|
||||||
|
CompilerResults results = CompileCode(compiler, parms, _source.ToString());
|
||||||
|
return results;
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
static ArrayList _mathMembers = new ArrayList();
|
||||||
|
static Hashtable _mathMembersMap = new Hashtable();
|
||||||
|
|
||||||
|
static void GetMathMemberNames()
|
||||||
|
{
|
||||||
|
// get a reflected assembly of the System assembly
|
||||||
|
Assembly systemAssembly = Assembly.GetAssembly(typeof(System.Math));
|
||||||
|
try
|
||||||
|
{
|
||||||
|
//cant call the entry method if the assembly is null
|
||||||
|
if (systemAssembly != null)
|
||||||
|
{
|
||||||
|
//Use reflection to get a reference to the Math class
|
||||||
|
|
||||||
|
Module[] modules = systemAssembly.GetModules(false);
|
||||||
|
Type[] types = modules[0].GetTypes();
|
||||||
|
|
||||||
|
//loop through each class that was defined and look for the first occurrance of the Math class
|
||||||
|
foreach (Type type in types)
|
||||||
|
{
|
||||||
|
if (type.Name == "Math")
|
||||||
|
{
|
||||||
|
// get all of the members of the math class and map them to the same member
|
||||||
|
// name in uppercase
|
||||||
|
MemberInfo[] mis = type.GetMembers();
|
||||||
|
foreach (MemberInfo mi in mis)
|
||||||
|
{
|
||||||
|
_mathMembers.Add(mi.Name);
|
||||||
|
_mathMembersMap[mi.Name.ToUpper()] = mi.Name;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
//if the entry point method does return in Int32, then capture it and return it
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
//if it got here, then there was no entry point method defined. Tell user about it
|
||||||
|
}
|
||||||
|
}
|
||||||
|
catch (Exception ex)
|
||||||
|
{
|
||||||
|
Console.WriteLine("Error: An exception occurred while executing the script", ex);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
/// <summary>
|
||||||
|
/// Runs the Calculate method in our on-the-fly assembly
|
||||||
|
/// </summary>
|
||||||
|
/// <param name="results"></param>
|
||||||
|
static private string RunCode(CompilerResults results)
|
||||||
|
{
|
||||||
|
Assembly executingAssembly = results.CompiledAssembly;
|
||||||
|
try
|
||||||
|
{
|
||||||
|
//cant call the entry method if the assembly is null
|
||||||
|
if (executingAssembly != null)
|
||||||
|
{
|
||||||
|
object assemblyInstance = executingAssembly.CreateInstance("ExpressionEvaluator.Calculator");
|
||||||
|
//Use reflection to call the static Main function
|
||||||
|
|
||||||
|
Module[] modules = executingAssembly.GetModules(false);
|
||||||
|
Type[] types = modules[0].GetTypes();
|
||||||
|
|
||||||
|
//loop through each class that was defined and look for the first occurrance of the entry point method
|
||||||
|
foreach (Type type in types)
|
||||||
|
{
|
||||||
|
MethodInfo[] mis = type.GetMethods();
|
||||||
|
foreach (MethodInfo mi in mis)
|
||||||
|
{
|
||||||
|
if (mi.Name == "Calculate")
|
||||||
|
{
|
||||||
|
object result = mi.Invoke(assemblyInstance, null);
|
||||||
|
return result.ToString();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
}
|
||||||
|
catch (Exception ex)
|
||||||
|
{
|
||||||
|
Console.WriteLine("Error: An exception occurred while executing the script", ex);
|
||||||
|
}
|
||||||
|
return "";
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
static CodeMemberField FieldVariable(string fieldName, string typeName, MemberAttributes accessLevel)
|
||||||
|
{
|
||||||
|
CodeMemberField field = new CodeMemberField(typeName, fieldName);
|
||||||
|
field.Attributes = accessLevel;
|
||||||
|
return field;
|
||||||
|
}
|
||||||
|
static CodeMemberField FieldVariable(string fieldName, Type type, MemberAttributes accessLevel)
|
||||||
|
{
|
||||||
|
CodeMemberField field = new CodeMemberField(type, fieldName);
|
||||||
|
field.Attributes = accessLevel;
|
||||||
|
return field;
|
||||||
|
}
|
||||||
|
|
||||||
|
/// <summary>
|
||||||
|
/// Very simplistic getter/setter properties
|
||||||
|
/// </summary>
|
||||||
|
/// <param name="propName"></param>
|
||||||
|
/// <param name="internalName"></param>
|
||||||
|
/// <param name="type"></param>
|
||||||
|
/// <returns></returns>
|
||||||
|
static CodeMemberProperty MakeProperty(string propertyName, string internalName, Type type)
|
||||||
|
{
|
||||||
|
CodeMemberProperty myProperty = new CodeMemberProperty();
|
||||||
|
myProperty.Name = propertyName;
|
||||||
|
myProperty.Comments.Add(new CodeCommentStatement(String.Format("The {0} property is the returned result", propertyName)));
|
||||||
|
myProperty.Attributes = MemberAttributes.Public;
|
||||||
|
myProperty.Type = new CodeTypeReference(type);
|
||||||
|
myProperty.HasGet = true;
|
||||||
|
myProperty.GetStatements.Add(
|
||||||
|
new CodeMethodReturnStatement(
|
||||||
|
new CodeFieldReferenceExpression(new CodeThisReferenceExpression(), internalName)));
|
||||||
|
|
||||||
|
myProperty.HasSet = true;
|
||||||
|
myProperty.SetStatements.Add(
|
||||||
|
new CodeAssignStatement(
|
||||||
|
new CodeFieldReferenceExpression(new CodeThisReferenceExpression(), internalName),
|
||||||
|
new CodePropertySetValueReferenceExpression()));
|
||||||
|
|
||||||
|
return myProperty;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
static StringBuilder _source = new StringBuilder();
|
||||||
|
|
||||||
|
/// <summary>
|
||||||
|
/// Main driving routine for building a class
|
||||||
|
/// </summary>
|
||||||
|
static void BuildClass(string expression)
|
||||||
|
{
|
||||||
|
// need a string to put the code into
|
||||||
|
_source = new StringBuilder();
|
||||||
|
StringWriter sw = new StringWriter(_source);
|
||||||
|
|
||||||
|
//Declare your provider and generator
|
||||||
|
CSharpCodeProvider codeProvider = new CSharpCodeProvider();
|
||||||
|
ICodeGenerator generator = codeProvider.CreateGenerator(sw);
|
||||||
|
CodeGeneratorOptions codeOpts = new CodeGeneratorOptions();
|
||||||
|
|
||||||
|
CodeNamespace myNamespace = new CodeNamespace("ExpressionEvaluator");
|
||||||
|
myNamespace.Imports.Add(new CodeNamespaceImport("System"));
|
||||||
|
myNamespace.Imports.Add(new CodeNamespaceImport("System.Windows.Forms"));
|
||||||
|
|
||||||
|
//Build the class declaration and member variables
|
||||||
|
CodeTypeDeclaration classDeclaration = new CodeTypeDeclaration();
|
||||||
|
classDeclaration.IsClass = true;
|
||||||
|
classDeclaration.Name = "Calculator";
|
||||||
|
classDeclaration.Attributes = MemberAttributes.Public;
|
||||||
|
classDeclaration.Members.Add(FieldVariable("answer", typeof(string), MemberAttributes.Private));
|
||||||
|
|
||||||
|
//default constructor
|
||||||
|
CodeConstructor defaultConstructor = new CodeConstructor();
|
||||||
|
defaultConstructor.Attributes = MemberAttributes.Public;
|
||||||
|
defaultConstructor.Comments.Add(new CodeCommentStatement("Default Constructor for class", true));
|
||||||
|
defaultConstructor.Statements.Add(new CodeSnippetStatement("//TODO: implement default constructor"));
|
||||||
|
classDeclaration.Members.Add(defaultConstructor);
|
||||||
|
|
||||||
|
//property
|
||||||
|
classDeclaration.Members.Add(MakeProperty("Answer", "answer", typeof(string)));
|
||||||
|
|
||||||
|
//Our Calculate Method
|
||||||
|
CodeMemberMethod myMethod = new CodeMemberMethod();
|
||||||
|
myMethod.Name = "Calculate";
|
||||||
|
myMethod.ReturnType = new CodeTypeReference(typeof(string));
|
||||||
|
myMethod.Comments.Add(new CodeCommentStatement("Calculate an expression", true));
|
||||||
|
myMethod.Attributes = MemberAttributes.Public;
|
||||||
|
myMethod.Statements.Add(new CodeAssignStatement(new CodeSnippetExpression("Object obj"), new CodeSnippetExpression(expression)));
|
||||||
|
myMethod.Statements.Add(new CodeAssignStatement(new CodeSnippetExpression("Answer"), new CodeSnippetExpression("obj.ToString()")));
|
||||||
|
myMethod.Statements.Add(
|
||||||
|
new CodeMethodReturnStatement(new CodeFieldReferenceExpression(new CodeThisReferenceExpression(), "Answer")));
|
||||||
|
classDeclaration.Members.Add(myMethod);
|
||||||
|
//write code
|
||||||
|
myNamespace.Types.Add(classDeclaration);
|
||||||
|
generator.GenerateCodeFromNamespace(myNamespace, sw, codeOpts);
|
||||||
|
sw.Flush();
|
||||||
|
sw.Close();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
|
@ -525,7 +525,7 @@ namespace ArdupilotMega
|
||||||
mode.mode = (byte)MAVLink.MAV_MODE.MAV_MODE_TEST2;
|
mode.mode = (byte)MAVLink.MAV_MODE.MAV_MODE_TEST2;
|
||||||
break;
|
break;
|
||||||
default:
|
default:
|
||||||
MessageBox.Show("No Mode Changed " + (int)Enum.Parse(Common.getModes(), modein));
|
CustomMessageBox.Show("No Mode Changed " + (int)Enum.Parse(Common.getModes(), modein));
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -553,12 +553,12 @@ namespace ArdupilotMega
|
||||||
mode.mode = (byte)MAVLink.MAV_MODE.MAV_MODE_AUTO;
|
mode.mode = (byte)MAVLink.MAV_MODE.MAV_MODE_AUTO;
|
||||||
break;
|
break;
|
||||||
default:
|
default:
|
||||||
MessageBox.Show("No Mode Changed " + (int)Enum.Parse(Common.getModes(), modein));
|
CustomMessageBox.Show("No Mode Changed " + (int)Enum.Parse(Common.getModes(), modein));
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
catch { System.Windows.Forms.MessageBox.Show("Failed to find Mode"); return false; }
|
catch { System.Windows.Forms.CustomMessageBox.Show("Failed to find Mode"); return false; }
|
||||||
|
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
@ -574,7 +574,7 @@ namespace ArdupilotMega
|
||||||
|
|
||||||
// Create a request using a URL that can receive a post.
|
// Create a request using a URL that can receive a post.
|
||||||
WebRequest request = WebRequest.Create(url);
|
WebRequest request = WebRequest.Create(url);
|
||||||
request.Timeout = 5000;
|
request.Timeout = 10000;
|
||||||
// Set the Method property of the request to POST.
|
// Set the Method property of the request to POST.
|
||||||
request.Method = "GET";
|
request.Method = "GET";
|
||||||
// Get the response.
|
// Get the response.
|
||||||
|
@ -652,7 +652,7 @@ namespace ArdupilotMega
|
||||||
form.MinimizeBox = false;
|
form.MinimizeBox = false;
|
||||||
form.MaximizeBox = false;
|
form.MaximizeBox = false;
|
||||||
|
|
||||||
MainV2.fixtheme(form);
|
ThemeManager.ApplyThemeTo(form);
|
||||||
|
|
||||||
form.Show();
|
form.Show();
|
||||||
form.Refresh();
|
form.Refresh();
|
||||||
|
@ -706,7 +706,7 @@ namespace ArdupilotMega
|
||||||
form.MinimizeBox = false;
|
form.MinimizeBox = false;
|
||||||
form.MaximizeBox = false;
|
form.MaximizeBox = false;
|
||||||
|
|
||||||
MainV2.fixtheme(form);
|
ThemeManager.ApplyThemeTo(form);
|
||||||
|
|
||||||
DialogResult dialogResult =form.ShowDialog();
|
DialogResult dialogResult =form.ShowDialog();
|
||||||
|
|
||||||
|
@ -760,7 +760,7 @@ namespace ArdupilotMega
|
||||||
form.AcceptButton = buttonOk;
|
form.AcceptButton = buttonOk;
|
||||||
form.CancelButton = buttonCancel;
|
form.CancelButton = buttonCancel;
|
||||||
|
|
||||||
MainV2.fixtheme(form);
|
ThemeManager.ApplyThemeTo(form);
|
||||||
|
|
||||||
DialogResult dialogResult = DialogResult.Cancel;
|
DialogResult dialogResult = DialogResult.Cancel;
|
||||||
|
|
||||||
|
|
|
@ -86,7 +86,7 @@ namespace System.IO.Ports
|
||||||
|
|
||||||
frmProgressReporter.UpdateProgressAndStatus(-1, "Connecting Mavlink UDP");
|
frmProgressReporter.UpdateProgressAndStatus(-1, "Connecting Mavlink UDP");
|
||||||
|
|
||||||
ArdupilotMega.MainV2.fixtheme(frmProgressReporter);
|
ArdupilotMega.ThemeManager.ApplyThemeTo(frmProgressReporter);
|
||||||
|
|
||||||
frmProgressReporter.RunBackgroundOperationAsync();
|
frmProgressReporter.RunBackgroundOperationAsync();
|
||||||
|
|
||||||
|
@ -143,7 +143,7 @@ namespace System.IO.Ports
|
||||||
client.Close();
|
client.Close();
|
||||||
}
|
}
|
||||||
log.Info(ex.ToString());
|
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");
|
System.Windows.Forms.CustomMessageBox.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);
|
throw new Exception("The socket/serialproxy is closed " + e);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
|
@ -0,0 +1,242 @@
|
||||||
|
using System;
|
||||||
|
using System.Drawing;
|
||||||
|
using System.Windows.Forms;
|
||||||
|
using ArdupilotMega.Controls;
|
||||||
|
using System.Text;
|
||||||
|
using ArdupilotMega;
|
||||||
|
|
||||||
|
namespace System.Windows.Forms
|
||||||
|
{
|
||||||
|
public static class CustomMessageBox
|
||||||
|
{
|
||||||
|
const int FORM_Y_MARGIN = 10;
|
||||||
|
const int FORM_X_MARGIN = 16;
|
||||||
|
|
||||||
|
static DialogResult _state = DialogResult.None;
|
||||||
|
|
||||||
|
public static DialogResult Show(string text)
|
||||||
|
{
|
||||||
|
return Show(text, string.Empty, MessageBoxButtons.OK, MessageBoxIcon.None);
|
||||||
|
}
|
||||||
|
|
||||||
|
public static DialogResult Show(string text, string caption)
|
||||||
|
{
|
||||||
|
return Show(text, caption, MessageBoxButtons.OK, MessageBoxIcon.None);
|
||||||
|
}
|
||||||
|
|
||||||
|
public static DialogResult Show(string text, string caption, MessageBoxButtons buttons)
|
||||||
|
{
|
||||||
|
return Show(text, caption, buttons, MessageBoxIcon.None);
|
||||||
|
}
|
||||||
|
|
||||||
|
public static DialogResult Show(string text, string caption, MessageBoxButtons buttons, MessageBoxIcon icon)
|
||||||
|
{
|
||||||
|
if (text == null)
|
||||||
|
text = "";
|
||||||
|
|
||||||
|
if (caption == null)
|
||||||
|
caption = "";
|
||||||
|
|
||||||
|
// ensure we are always in a known state
|
||||||
|
_state = DialogResult.None;
|
||||||
|
|
||||||
|
// convert to nice wrapped lines.
|
||||||
|
text = AddNewLinesToText(text);
|
||||||
|
// get pixel width and height
|
||||||
|
Size textSize = TextRenderer.MeasureText(text, SystemFonts.DefaultFont);
|
||||||
|
// allow for icon
|
||||||
|
if (icon != MessageBoxIcon.None)
|
||||||
|
textSize.Width += SystemIcons.Question.Width;
|
||||||
|
|
||||||
|
var msgBoxFrm = new Form
|
||||||
|
{
|
||||||
|
FormBorderStyle = FormBorderStyle.FixedDialog,
|
||||||
|
ShowInTaskbar = false,
|
||||||
|
StartPosition = FormStartPosition.CenterScreen,
|
||||||
|
Text = caption,
|
||||||
|
MaximizeBox = false,
|
||||||
|
MinimizeBox = false,
|
||||||
|
Width = textSize.Width + 50,
|
||||||
|
Height = textSize.Height + 100,
|
||||||
|
TopMost = true,
|
||||||
|
};
|
||||||
|
|
||||||
|
Rectangle screenRectangle = msgBoxFrm.RectangleToScreen(msgBoxFrm.ClientRectangle);
|
||||||
|
int titleHeight = screenRectangle.Top - msgBoxFrm.Top;
|
||||||
|
|
||||||
|
var lblMessage = new Label
|
||||||
|
{
|
||||||
|
Left = 58,
|
||||||
|
Top = 15,
|
||||||
|
Width = textSize.Width + 10,
|
||||||
|
Height = textSize.Height + 10,
|
||||||
|
Text = text
|
||||||
|
};
|
||||||
|
|
||||||
|
msgBoxFrm.Controls.Add(lblMessage);
|
||||||
|
|
||||||
|
var actualIcon = getMessageBoxIcon(icon);
|
||||||
|
|
||||||
|
if (actualIcon == null)
|
||||||
|
{
|
||||||
|
lblMessage.Location = new Point(FORM_X_MARGIN, FORM_Y_MARGIN);
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
var iconPbox = new PictureBox
|
||||||
|
{
|
||||||
|
Image = actualIcon.ToBitmap(),
|
||||||
|
Location = new Point(FORM_X_MARGIN, FORM_Y_MARGIN)
|
||||||
|
};
|
||||||
|
msgBoxFrm.Controls.Add(iconPbox);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
AddButtonsToForm(msgBoxFrm, buttons);
|
||||||
|
|
||||||
|
// display even if theme fails
|
||||||
|
try
|
||||||
|
{
|
||||||
|
ThemeManager.ApplyThemeTo(msgBoxFrm);
|
||||||
|
}
|
||||||
|
catch { }
|
||||||
|
|
||||||
|
if (System.Windows.Forms.Application.OpenForms.Count > 0)
|
||||||
|
{
|
||||||
|
msgBoxFrm.StartPosition = FormStartPosition.Manual;
|
||||||
|
Form parentForm = System.Windows.Forms.Application.OpenForms[0];
|
||||||
|
// center of first form
|
||||||
|
msgBoxFrm.Location = new Point(parentForm.Location.X + parentForm.Width / 2 - msgBoxFrm.Width / 2,
|
||||||
|
parentForm.Location.Y + parentForm.Height / 2 - msgBoxFrm.Height / 2);
|
||||||
|
DialogResult test = msgBoxFrm.ShowDialog();
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
DialogResult test = msgBoxFrm.ShowDialog();
|
||||||
|
}
|
||||||
|
|
||||||
|
DialogResult answer = _state;
|
||||||
|
|
||||||
|
return answer;
|
||||||
|
}
|
||||||
|
|
||||||
|
static void msgBoxFrm_FormClosing(object sender, FormClosingEventArgs e)
|
||||||
|
{
|
||||||
|
throw new NotImplementedException();
|
||||||
|
}
|
||||||
|
|
||||||
|
// from http://stackoverflow.com/questions/2512781/winforms-big-paragraph-tooltip/2512895#2512895
|
||||||
|
private static int maximumSingleLineTooltipLength = 85;
|
||||||
|
|
||||||
|
private static string AddNewLinesToText(string text)
|
||||||
|
{
|
||||||
|
if (text.Length < maximumSingleLineTooltipLength)
|
||||||
|
return text;
|
||||||
|
int lineLength = maximumSingleLineTooltipLength;
|
||||||
|
StringBuilder sb = new StringBuilder();
|
||||||
|
int currentLinePosition = 0;
|
||||||
|
for (int textIndex = 0; textIndex < text.Length; textIndex++)
|
||||||
|
{
|
||||||
|
// If we have reached the target line length and the next
|
||||||
|
// character is whitespace then begin a new line.
|
||||||
|
if (currentLinePosition >= lineLength &&
|
||||||
|
char.IsWhiteSpace(text[textIndex]))
|
||||||
|
{
|
||||||
|
sb.Append(Environment.NewLine);
|
||||||
|
currentLinePosition = 0;
|
||||||
|
}
|
||||||
|
// If we have just started a new line, skip all the whitespace.
|
||||||
|
if (currentLinePosition == 0)
|
||||||
|
while (textIndex < text.Length && char.IsWhiteSpace(text[textIndex]))
|
||||||
|
textIndex++;
|
||||||
|
// Append the next character.
|
||||||
|
if (textIndex < text.Length) sb.Append(text[textIndex]);
|
||||||
|
currentLinePosition++;
|
||||||
|
}
|
||||||
|
return sb.ToString();
|
||||||
|
}
|
||||||
|
|
||||||
|
private static void AddButtonsToForm(Form msgBoxFrm, MessageBoxButtons buttons)
|
||||||
|
{
|
||||||
|
Rectangle screenRectangle = msgBoxFrm.RectangleToScreen(msgBoxFrm.ClientRectangle);
|
||||||
|
int titleHeight = screenRectangle.Top - msgBoxFrm.Top;
|
||||||
|
|
||||||
|
var t = Type.GetType("Mono.Runtime");
|
||||||
|
if ((t != null))
|
||||||
|
titleHeight = 25;
|
||||||
|
|
||||||
|
switch (buttons)
|
||||||
|
{
|
||||||
|
case MessageBoxButtons.OK:
|
||||||
|
var but = new MyButton
|
||||||
|
{
|
||||||
|
Size = new Size(75, 23),
|
||||||
|
Text = "OK",
|
||||||
|
Left = msgBoxFrm.Width - 75 - FORM_X_MARGIN,
|
||||||
|
Top = msgBoxFrm.Height - 23 - FORM_Y_MARGIN - titleHeight
|
||||||
|
};
|
||||||
|
|
||||||
|
but.Click += delegate { _state = DialogResult.OK; msgBoxFrm.Close(); };
|
||||||
|
msgBoxFrm.Controls.Add(but);
|
||||||
|
msgBoxFrm.AcceptButton = but;
|
||||||
|
break;
|
||||||
|
|
||||||
|
case MessageBoxButtons.YesNo:
|
||||||
|
|
||||||
|
if (msgBoxFrm.Width < (75 * 2 + FORM_X_MARGIN * 3))
|
||||||
|
msgBoxFrm.Width = (75 * 2 + FORM_X_MARGIN * 3);
|
||||||
|
|
||||||
|
var butyes = new MyButton
|
||||||
|
{
|
||||||
|
Size = new Size(75, 23),
|
||||||
|
Text = "Yes",
|
||||||
|
Left = msgBoxFrm.Width - 75 * 2 - FORM_X_MARGIN * 2,
|
||||||
|
Top = msgBoxFrm.Height - 23 - FORM_Y_MARGIN - titleHeight
|
||||||
|
};
|
||||||
|
|
||||||
|
butyes.Click += delegate { _state = DialogResult.Yes; msgBoxFrm.Close(); };
|
||||||
|
msgBoxFrm.Controls.Add(butyes);
|
||||||
|
msgBoxFrm.AcceptButton = butyes;
|
||||||
|
|
||||||
|
var butno = new MyButton
|
||||||
|
{
|
||||||
|
Size = new Size(75, 23),
|
||||||
|
Text = "No",
|
||||||
|
Left = msgBoxFrm.Width - 75 - FORM_X_MARGIN,
|
||||||
|
Top = msgBoxFrm.Height - 23 - FORM_Y_MARGIN - titleHeight
|
||||||
|
};
|
||||||
|
|
||||||
|
butno.Click += delegate { _state = DialogResult.No; msgBoxFrm.Close(); };
|
||||||
|
msgBoxFrm.Controls.Add(butno);
|
||||||
|
msgBoxFrm.CancelButton = butno;
|
||||||
|
break;
|
||||||
|
|
||||||
|
default:
|
||||||
|
throw new NotImplementedException("Only MessageBoxButtons.OK and YesNo supported at this time");
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
/// <summary>
|
||||||
|
/// Get system icon for MessageBoxIcon.
|
||||||
|
/// </summary>
|
||||||
|
/// <param name="icon">The MessageBoxIcon value.</param>
|
||||||
|
/// <returns>SystemIcon type Icon.</returns>
|
||||||
|
private static Icon getMessageBoxIcon(MessageBoxIcon icon)
|
||||||
|
{
|
||||||
|
switch (icon)
|
||||||
|
{
|
||||||
|
case MessageBoxIcon.Asterisk:
|
||||||
|
return SystemIcons.Asterisk;
|
||||||
|
case MessageBoxIcon.Error:
|
||||||
|
return SystemIcons.Error;
|
||||||
|
case MessageBoxIcon.Exclamation:
|
||||||
|
return SystemIcons.Exclamation;
|
||||||
|
case MessageBoxIcon.Question:
|
||||||
|
return SystemIcons.Question;
|
||||||
|
default:
|
||||||
|
return null;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
}
|
|
@ -0,0 +1,242 @@
|
||||||
|
using System;
|
||||||
|
using System.Drawing;
|
||||||
|
using System.Windows.Forms;
|
||||||
|
using ArdupilotMega.Controls;
|
||||||
|
using System.Text;
|
||||||
|
using ArdupilotMega;
|
||||||
|
|
||||||
|
namespace System.Windows.Forms
|
||||||
|
{
|
||||||
|
public static class MessageBox
|
||||||
|
{
|
||||||
|
const int FORM_Y_MARGIN = 10;
|
||||||
|
const int FORM_X_MARGIN = 16;
|
||||||
|
|
||||||
|
static DialogResult _state = DialogResult.None;
|
||||||
|
|
||||||
|
public static DialogResult Show(string text)
|
||||||
|
{
|
||||||
|
return Show(text, string.Empty, MessageBoxButtons.OK, MessageBoxIcon.None);
|
||||||
|
}
|
||||||
|
|
||||||
|
public static DialogResult Show(string text, string caption)
|
||||||
|
{
|
||||||
|
return Show(text, caption, MessageBoxButtons.OK, MessageBoxIcon.None);
|
||||||
|
}
|
||||||
|
|
||||||
|
public static DialogResult Show(string text, string caption, MessageBoxButtons buttons)
|
||||||
|
{
|
||||||
|
return Show(text, caption, buttons, MessageBoxIcon.None);
|
||||||
|
}
|
||||||
|
|
||||||
|
public static DialogResult Show(string text, string caption, MessageBoxButtons buttons, MessageBoxIcon icon)
|
||||||
|
{
|
||||||
|
if (text == null)
|
||||||
|
text = "";
|
||||||
|
|
||||||
|
if (caption == null)
|
||||||
|
caption = "";
|
||||||
|
|
||||||
|
// ensure we are always in a known state
|
||||||
|
_state = DialogResult.None;
|
||||||
|
|
||||||
|
// convert to nice wrapped lines.
|
||||||
|
text = AddNewLinesToText(text);
|
||||||
|
// get pixel width and height
|
||||||
|
Size textSize = TextRenderer.MeasureText(text, SystemFonts.DefaultFont);
|
||||||
|
// allow for icon
|
||||||
|
if (icon != MessageBoxIcon.None)
|
||||||
|
textSize.Width += SystemIcons.Question.Width;
|
||||||
|
|
||||||
|
var msgBoxFrm = new Form
|
||||||
|
{
|
||||||
|
FormBorderStyle = FormBorderStyle.FixedDialog,
|
||||||
|
ShowInTaskbar = false,
|
||||||
|
StartPosition = FormStartPosition.CenterScreen,
|
||||||
|
Text = caption,
|
||||||
|
MaximizeBox = false,
|
||||||
|
MinimizeBox = false,
|
||||||
|
Width = textSize.Width + 50,
|
||||||
|
Height = textSize.Height + 100,
|
||||||
|
TopMost = true,
|
||||||
|
};
|
||||||
|
|
||||||
|
Rectangle screenRectangle = msgBoxFrm.RectangleToScreen(msgBoxFrm.ClientRectangle);
|
||||||
|
int titleHeight = screenRectangle.Top - msgBoxFrm.Top;
|
||||||
|
|
||||||
|
var lblMessage = new Label
|
||||||
|
{
|
||||||
|
Left = 58,
|
||||||
|
Top = 15,
|
||||||
|
Width = textSize.Width + 10,
|
||||||
|
Height = textSize.Height + 10,
|
||||||
|
Text = text
|
||||||
|
};
|
||||||
|
|
||||||
|
msgBoxFrm.Controls.Add(lblMessage);
|
||||||
|
|
||||||
|
var actualIcon = getMessageBoxIcon(icon);
|
||||||
|
|
||||||
|
if (actualIcon == null)
|
||||||
|
{
|
||||||
|
lblMessage.Location = new Point(FORM_X_MARGIN, FORM_Y_MARGIN);
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
var iconPbox = new PictureBox
|
||||||
|
{
|
||||||
|
Image = actualIcon.ToBitmap(),
|
||||||
|
Location = new Point(FORM_X_MARGIN, FORM_Y_MARGIN)
|
||||||
|
};
|
||||||
|
msgBoxFrm.Controls.Add(iconPbox);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
AddButtonsToForm(msgBoxFrm, buttons);
|
||||||
|
|
||||||
|
// display even if theme fails
|
||||||
|
try
|
||||||
|
{
|
||||||
|
ThemeManager.ApplyThemeTo(msgBoxFrm);
|
||||||
|
}
|
||||||
|
catch { }
|
||||||
|
|
||||||
|
if (System.Windows.Forms.Application.OpenForms.Count > 0)
|
||||||
|
{
|
||||||
|
msgBoxFrm.StartPosition = FormStartPosition.Manual;
|
||||||
|
Form parentForm = System.Windows.Forms.Application.OpenForms[0];
|
||||||
|
// center of first form
|
||||||
|
msgBoxFrm.Location = new Point(parentForm.Location.X + parentForm.Width / 2 - msgBoxFrm.Width / 2,
|
||||||
|
parentForm.Location.Y + parentForm.Height / 2 - msgBoxFrm.Height / 2);
|
||||||
|
DialogResult test = msgBoxFrm.ShowDialog();
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
DialogResult test = msgBoxFrm.ShowDialog();
|
||||||
|
}
|
||||||
|
|
||||||
|
DialogResult answer = _state;
|
||||||
|
|
||||||
|
return answer;
|
||||||
|
}
|
||||||
|
|
||||||
|
static void msgBoxFrm_FormClosing(object sender, FormClosingEventArgs e)
|
||||||
|
{
|
||||||
|
throw new NotImplementedException();
|
||||||
|
}
|
||||||
|
|
||||||
|
// from http://stackoverflow.com/questions/2512781/winforms-big-paragraph-tooltip/2512895#2512895
|
||||||
|
private static int maximumSingleLineTooltipLength = 85;
|
||||||
|
|
||||||
|
private static string AddNewLinesToText(string text)
|
||||||
|
{
|
||||||
|
if (text.Length < maximumSingleLineTooltipLength)
|
||||||
|
return text;
|
||||||
|
int lineLength = maximumSingleLineTooltipLength;
|
||||||
|
StringBuilder sb = new StringBuilder();
|
||||||
|
int currentLinePosition = 0;
|
||||||
|
for (int textIndex = 0; textIndex < text.Length; textIndex++)
|
||||||
|
{
|
||||||
|
// If we have reached the target line length and the next
|
||||||
|
// character is whitespace then begin a new line.
|
||||||
|
if (currentLinePosition >= lineLength &&
|
||||||
|
char.IsWhiteSpace(text[textIndex]))
|
||||||
|
{
|
||||||
|
sb.Append(Environment.NewLine);
|
||||||
|
currentLinePosition = 0;
|
||||||
|
}
|
||||||
|
// If we have just started a new line, skip all the whitespace.
|
||||||
|
if (currentLinePosition == 0)
|
||||||
|
while (textIndex < text.Length && char.IsWhiteSpace(text[textIndex]))
|
||||||
|
textIndex++;
|
||||||
|
// Append the next character.
|
||||||
|
if (textIndex < text.Length) sb.Append(text[textIndex]);
|
||||||
|
currentLinePosition++;
|
||||||
|
}
|
||||||
|
return sb.ToString();
|
||||||
|
}
|
||||||
|
|
||||||
|
private static void AddButtonsToForm(Form msgBoxFrm, MessageBoxButtons buttons)
|
||||||
|
{
|
||||||
|
Rectangle screenRectangle = msgBoxFrm.RectangleToScreen(msgBoxFrm.ClientRectangle);
|
||||||
|
int titleHeight = screenRectangle.Top - msgBoxFrm.Top;
|
||||||
|
|
||||||
|
var t = Type.GetType("Mono.Runtime");
|
||||||
|
if ((t != null))
|
||||||
|
titleHeight = 25;
|
||||||
|
|
||||||
|
switch (buttons)
|
||||||
|
{
|
||||||
|
case MessageBoxButtons.OK:
|
||||||
|
var but = new MyButton
|
||||||
|
{
|
||||||
|
Size = new Size(75, 23),
|
||||||
|
Text = "OK",
|
||||||
|
Left = msgBoxFrm.Width - 75 - FORM_X_MARGIN,
|
||||||
|
Top = msgBoxFrm.Height - 23 - FORM_Y_MARGIN - titleHeight
|
||||||
|
};
|
||||||
|
|
||||||
|
but.Click += delegate { _state = DialogResult.OK; msgBoxFrm.Close(); };
|
||||||
|
msgBoxFrm.Controls.Add(but);
|
||||||
|
msgBoxFrm.AcceptButton = but;
|
||||||
|
break;
|
||||||
|
|
||||||
|
case MessageBoxButtons.YesNo:
|
||||||
|
|
||||||
|
if (msgBoxFrm.Width < (75 * 2 + FORM_X_MARGIN * 3))
|
||||||
|
msgBoxFrm.Width = (75 * 2 + FORM_X_MARGIN * 3);
|
||||||
|
|
||||||
|
var butyes = new MyButton
|
||||||
|
{
|
||||||
|
Size = new Size(75, 23),
|
||||||
|
Text = "Yes",
|
||||||
|
Left = msgBoxFrm.Width - 75 * 2 - FORM_X_MARGIN * 2,
|
||||||
|
Top = msgBoxFrm.Height - 23 - FORM_Y_MARGIN - titleHeight
|
||||||
|
};
|
||||||
|
|
||||||
|
butyes.Click += delegate { _state = DialogResult.Yes; msgBoxFrm.Close(); };
|
||||||
|
msgBoxFrm.Controls.Add(butyes);
|
||||||
|
msgBoxFrm.AcceptButton = butyes;
|
||||||
|
|
||||||
|
var butno = new MyButton
|
||||||
|
{
|
||||||
|
Size = new Size(75, 23),
|
||||||
|
Text = "No",
|
||||||
|
Left = msgBoxFrm.Width - 75 - FORM_X_MARGIN,
|
||||||
|
Top = msgBoxFrm.Height - 23 - FORM_Y_MARGIN - titleHeight
|
||||||
|
};
|
||||||
|
|
||||||
|
butno.Click += delegate { _state = DialogResult.No; msgBoxFrm.Close(); };
|
||||||
|
msgBoxFrm.Controls.Add(butno);
|
||||||
|
msgBoxFrm.CancelButton = butno;
|
||||||
|
break;
|
||||||
|
|
||||||
|
default:
|
||||||
|
throw new NotImplementedException("Only MessageBoxButtons.OK and YesNo supported at this time");
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
/// <summary>
|
||||||
|
/// Get system icon for MessageBoxIcon.
|
||||||
|
/// </summary>
|
||||||
|
/// <param name="icon">The MessageBoxIcon value.</param>
|
||||||
|
/// <returns>SystemIcon type Icon.</returns>
|
||||||
|
private static Icon getMessageBoxIcon(MessageBoxIcon icon)
|
||||||
|
{
|
||||||
|
switch (icon)
|
||||||
|
{
|
||||||
|
case MessageBoxIcon.Asterisk:
|
||||||
|
return SystemIcons.Asterisk;
|
||||||
|
case MessageBoxIcon.Error:
|
||||||
|
return SystemIcons.Error;
|
||||||
|
case MessageBoxIcon.Exclamation:
|
||||||
|
return SystemIcons.Exclamation;
|
||||||
|
case MessageBoxIcon.Question:
|
||||||
|
return SystemIcons.Question;
|
||||||
|
default:
|
||||||
|
return null;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
}
|
|
@ -19,6 +19,15 @@ namespace ArdupilotMega
|
||||||
|
|
||||||
bool inOnPaint = false;
|
bool inOnPaint = false;
|
||||||
|
|
||||||
|
public Color BGGradTop = Color.FromArgb(0x94, 0xc1, 0x1f);
|
||||||
|
|
||||||
|
public Color BGGradBot = Color.FromArgb(0xcd, 0xe2, 0x96);
|
||||||
|
|
||||||
|
// i want to ignore forecolor
|
||||||
|
public Color TextColor = Color.FromArgb(0x40, 0x57, 0x04);
|
||||||
|
|
||||||
|
public Color Outline = Color.FromArgb(0x79, 0x94, 0x29);
|
||||||
|
|
||||||
protected override void OnPaint(PaintEventArgs pevent)
|
protected override void OnPaint(PaintEventArgs pevent)
|
||||||
{
|
{
|
||||||
//base.OnPaint(pevent);
|
//base.OnPaint(pevent);
|
||||||
|
@ -36,9 +45,9 @@ namespace ArdupilotMega
|
||||||
|
|
||||||
Rectangle outside = new Rectangle(0, 0, this.Width, this.Height);
|
Rectangle outside = new Rectangle(0, 0, this.Width, this.Height);
|
||||||
|
|
||||||
LinearGradientBrush linear = new LinearGradientBrush(outside, Color.FromArgb(0x94, 0xc1, 0x1f), Color.FromArgb(0xcd, 0xe2, 0x96), LinearGradientMode.Vertical);
|
LinearGradientBrush linear = new LinearGradientBrush(outside, BGGradTop, BGGradBot, LinearGradientMode.Vertical);
|
||||||
|
|
||||||
Pen mypen = new Pen(Color.FromArgb(0x79, 0x94, 0x29), 2);
|
Pen mypen = new Pen(Outline, 2);
|
||||||
/*
|
/*
|
||||||
gr.FillRectangle(new SolidBrush(Color.FromArgb(0x26, 0x27, 0x28)), outside);
|
gr.FillRectangle(new SolidBrush(Color.FromArgb(0x26, 0x27, 0x28)), outside);
|
||||||
|
|
||||||
|
@ -71,7 +80,7 @@ namespace ArdupilotMega
|
||||||
gr.DrawRectangle(mypen, outside);
|
gr.DrawRectangle(mypen, outside);
|
||||||
|
|
||||||
|
|
||||||
SolidBrush mybrush = new SolidBrush(Color.FromArgb(0x40, 0x57, 0x04));
|
SolidBrush mybrush = new SolidBrush(TextColor);
|
||||||
|
|
||||||
if (mouseover)
|
if (mouseover)
|
||||||
{
|
{
|
||||||
|
|
|
@ -1,64 +0,0 @@
|
||||||
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
|
|
||||||
{
|
|
||||||
public partial class ProgressReporter : Form
|
|
||||||
{
|
|
||||||
bool cancel = false;
|
|
||||||
|
|
||||||
public ProgressReporter()
|
|
||||||
{
|
|
||||||
InitializeComponent();
|
|
||||||
cancel = false;
|
|
||||||
}
|
|
||||||
|
|
||||||
private void btnCancel_Click(object sender, EventArgs e)
|
|
||||||
{
|
|
||||||
cancel = true;
|
|
||||||
this.Close();
|
|
||||||
}
|
|
||||||
|
|
||||||
public void updateProgressAndStatus(int progress, string status)
|
|
||||||
{
|
|
||||||
//Console.WriteLine(progress + " " + status);
|
|
||||||
|
|
||||||
if (cancel)
|
|
||||||
{
|
|
||||||
throw new Exception("User Canceled");
|
|
||||||
}
|
|
||||||
|
|
||||||
if (this.IsDisposed)
|
|
||||||
{
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
|
|
||||||
try
|
|
||||||
{
|
|
||||||
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;
|
|
||||||
}
|
|
||||||
});
|
|
||||||
}
|
|
||||||
catch { }
|
|
||||||
|
|
||||||
System.Windows.Forms.Application.DoEvents();
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
|
@ -1,94 +0,0 @@
|
||||||
using System.Windows.Forms;
|
|
||||||
|
|
||||||
namespace ArdupilotMega
|
|
||||||
{
|
|
||||||
partial class ProgressReporter
|
|
||||||
{
|
|
||||||
/// <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.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(12, 82);
|
|
||||||
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(276, 66);
|
|
||||||
this.lblProgressMessage.TabIndex = 1;
|
|
||||||
this.lblProgressMessage.Text = "label1";
|
|
||||||
//
|
|
||||||
// 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);
|
|
||||||
//
|
|
||||||
// ProgressReporter
|
|
||||||
//
|
|
||||||
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.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 = "ProgressReporter";
|
|
||||||
this.SizeGripStyle = System.Windows.Forms.SizeGripStyle.Hide;
|
|
||||||
this.StartPosition = System.Windows.Forms.FormStartPosition.CenterParent;
|
|
||||||
this.Text = "Progress";
|
|
||||||
this.ResumeLayout(false);
|
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
#endregion
|
|
||||||
|
|
||||||
private ProgressBar progressBar1;
|
|
||||||
private System.Windows.Forms.Label lblProgressMessage;
|
|
||||||
private Button btnCancel;
|
|
||||||
}
|
|
||||||
}
|
|
|
@ -1,120 +0,0 @@
|
||||||
<?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>
|
|
|
@ -42,7 +42,16 @@ namespace ArdupilotMega.Controls
|
||||||
|
|
||||||
private void RunBackgroundOperation(object o)
|
private void RunBackgroundOperation(object o)
|
||||||
{
|
{
|
||||||
Thread.CurrentThread.Name = "ProgressReporterDialogue Background thread";
|
try
|
||||||
|
{
|
||||||
|
Thread.CurrentThread.Name = "ProgressReporterDialogue Background thread";
|
||||||
|
}
|
||||||
|
catch { } // ok on windows - fails on mono
|
||||||
|
|
||||||
|
// mono fix - ensure the dialog is running
|
||||||
|
while (this.IsHandleCreated == false)
|
||||||
|
System.Threading.Thread.Sleep(5);
|
||||||
|
|
||||||
try
|
try
|
||||||
{
|
{
|
||||||
if (this.DoWork != null) this.DoWork(this, doWorkArgs);
|
if (this.DoWork != null) this.DoWork(this, doWorkArgs);
|
||||||
|
@ -56,6 +65,7 @@ namespace ArdupilotMega.Controls
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
if (doWorkArgs.CancelRequested && doWorkArgs.CancelAcknowledged)
|
if (doWorkArgs.CancelRequested && doWorkArgs.CancelAcknowledged)
|
||||||
{
|
{
|
||||||
ShowDoneCancelled();
|
ShowDoneCancelled();
|
||||||
|
@ -201,7 +211,7 @@ namespace ArdupilotMega.Controls
|
||||||
+ Environment.NewLine + Environment.NewLine
|
+ Environment.NewLine + Environment.NewLine
|
||||||
+ this.workerException.StackTrace;
|
+ this.workerException.StackTrace;
|
||||||
|
|
||||||
MessageBox.Show(message,"Exception Details",MessageBoxButtons.OK,MessageBoxIcon.Information);
|
CustomMessageBox.Show(message,"Exception Details",MessageBoxButtons.OK,MessageBoxIcon.Information);
|
||||||
}
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
|
@ -28,7 +28,7 @@ namespace ArdupilotMega
|
||||||
|
|
||||||
if (planlocs.Count <= 1)
|
if (planlocs.Count <= 1)
|
||||||
{
|
{
|
||||||
MessageBox.Show("Please plan something first");
|
CustomMessageBox.Show("Please plan something first");
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -113,7 +113,7 @@ namespace ArdupilotMega
|
||||||
|
|
||||||
if (list.Count <= 2 || coords.Length > (2048 - 256) || distance > 50000)
|
if (list.Count <= 2 || coords.Length > (2048 - 256) || distance > 50000)
|
||||||
{
|
{
|
||||||
MessageBox.Show("To many/few WP's or to Big a Distance " + (distance/1000) + "km");
|
CustomMessageBox.Show("To many/few WP's or to Big a Distance " + (distance/1000) + "km");
|
||||||
return answer;
|
return answer;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -145,7 +145,7 @@ namespace ArdupilotMega
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
catch { MessageBox.Show("Error getting GE data"); }
|
catch { CustomMessageBox.Show("Error getting GE data"); }
|
||||||
|
|
||||||
return answer;
|
return answer;
|
||||||
}
|
}
|
||||||
|
|
|
@ -590,7 +590,7 @@ namespace ArdupilotMega.GCSViews
|
||||||
string line = sr.ReadLine();
|
string line = sr.ReadLine();
|
||||||
|
|
||||||
if (line.Contains("NOTE:"))
|
if (line.Contains("NOTE:"))
|
||||||
MessageBox.Show(line, "Saved Note");
|
CustomMessageBox.Show(line, "Saved Note");
|
||||||
|
|
||||||
int index = line.IndexOf(',');
|
int index = line.IndexOf(',');
|
||||||
|
|
||||||
|
@ -711,7 +711,7 @@ namespace ArdupilotMega.GCSViews
|
||||||
catch { }
|
catch { }
|
||||||
|
|
||||||
}
|
}
|
||||||
catch { MessageBox.Show("Set " + value + " Failed"); }
|
catch { CustomMessageBox.Show("Set " + value + " Failed"); }
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -724,7 +724,7 @@ namespace ArdupilotMega.GCSViews
|
||||||
{
|
{
|
||||||
if (!MainV2.comPort.BaseStream.IsOpen)
|
if (!MainV2.comPort.BaseStream.IsOpen)
|
||||||
{
|
{
|
||||||
MessageBox.Show("Please Connect First");
|
CustomMessageBox.Show("Please Connect First");
|
||||||
ConfigTabs.SelectedIndex = 0;
|
ConfigTabs.SelectedIndex = 0;
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
|
@ -734,7 +734,7 @@ namespace ArdupilotMega.GCSViews
|
||||||
|
|
||||||
temp.Configuration = this;
|
temp.Configuration = this;
|
||||||
|
|
||||||
MainV2.fixtheme(temp);
|
ThemeManager.ApplyThemeTo(temp);
|
||||||
|
|
||||||
temp.ShowDialog();
|
temp.ShowDialog();
|
||||||
|
|
||||||
|
@ -764,7 +764,7 @@ namespace ArdupilotMega.GCSViews
|
||||||
|
|
||||||
BUT_videostart.Enabled = false;
|
BUT_videostart.Enabled = false;
|
||||||
}
|
}
|
||||||
catch (Exception ex) { MessageBox.Show("Camera Fail: " + ex.Message); }
|
catch (Exception ex) { CustomMessageBox.Show("Camera Fail: " + ex.Message); }
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -818,7 +818,7 @@ namespace ArdupilotMega.GCSViews
|
||||||
}
|
}
|
||||||
catch (Exception ex)
|
catch (Exception ex)
|
||||||
{
|
{
|
||||||
MessageBox.Show("Can not add video source\n" + ex.ToString());
|
CustomMessageBox.Show("Can not add video source\n" + ex.ToString());
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -951,7 +951,7 @@ namespace ArdupilotMega.GCSViews
|
||||||
|
|
||||||
|
|
||||||
}
|
}
|
||||||
catch { MessageBox.Show("Error: getting param list"); }
|
catch { CustomMessageBox.Show("Error: getting param list"); }
|
||||||
|
|
||||||
|
|
||||||
((MyButton)sender).Enabled = true;
|
((MyButton)sender).Enabled = true;
|
||||||
|
@ -985,7 +985,7 @@ namespace ArdupilotMega.GCSViews
|
||||||
private void BUT_Joystick_Click(object sender, EventArgs e)
|
private void BUT_Joystick_Click(object sender, EventArgs e)
|
||||||
{
|
{
|
||||||
Form joy = new JoystickSetup();
|
Form joy = new JoystickSetup();
|
||||||
MainV2.fixtheme(joy);
|
ThemeManager.ApplyThemeTo(joy);
|
||||||
joy.Show();
|
joy.Show();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -1122,7 +1122,7 @@ namespace ArdupilotMega.GCSViews
|
||||||
string line = sr.ReadLine();
|
string line = sr.ReadLine();
|
||||||
|
|
||||||
if (line.Contains("NOTE:"))
|
if (line.Contains("NOTE:"))
|
||||||
MessageBox.Show(line, "Saved Note");
|
CustomMessageBox.Show(line, "Saved Note");
|
||||||
|
|
||||||
int index = line.IndexOf(',');
|
int index = line.IndexOf(',');
|
||||||
|
|
||||||
|
@ -1146,7 +1146,7 @@ namespace ArdupilotMega.GCSViews
|
||||||
sr.Close();
|
sr.Close();
|
||||||
|
|
||||||
ParamCompare temp = new ParamCompare(this, param, param2);
|
ParamCompare temp = new ParamCompare(this, param, param2);
|
||||||
MainV2.fixtheme(temp);
|
ThemeManager.ApplyThemeTo(temp);
|
||||||
temp.ShowDialog();
|
temp.ShowDialog();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -1155,7 +1155,7 @@ namespace ArdupilotMega.GCSViews
|
||||||
{
|
{
|
||||||
if (startup)
|
if (startup)
|
||||||
return;
|
return;
|
||||||
MessageBox.Show("You need to restart the planner for this to take effect");
|
CustomMessageBox.Show("You need to restart the planner for this to take effect");
|
||||||
MainV2.config["CHK_GDIPlus"] = CHK_GDIPlus.Checked.ToString();
|
MainV2.config["CHK_GDIPlus"] = CHK_GDIPlus.Checked.ToString();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -141,7 +141,7 @@ namespace ArdupilotMega.GCSViews
|
||||||
}
|
}
|
||||||
catch (Exception ex)
|
catch (Exception ex)
|
||||||
{
|
{
|
||||||
MessageBox.Show("Failed to get Firmware List : " + ex.Message);
|
CustomMessageBox.Show("Failed to get Firmware List : " + ex.Message);
|
||||||
}
|
}
|
||||||
log.Info("FW load done");
|
log.Info("FW load done");
|
||||||
|
|
||||||
|
@ -211,12 +211,12 @@ namespace ArdupilotMega.GCSViews
|
||||||
// none found
|
// none found
|
||||||
if (items.Count == 0)
|
if (items.Count == 0)
|
||||||
{
|
{
|
||||||
MessageBox.Show("The requested firmware was not found.");
|
CustomMessageBox.Show("The requested firmware was not found.");
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
else if (items.Count == 1) // 1 found so accept it
|
else if (items.Count == 1) // 1 found so accept it
|
||||||
{
|
{
|
||||||
DialogResult dr = MessageBox.Show("Are you sure you want to upload " + items[0].name + "?", "Continue", MessageBoxButtons.YesNo);
|
DialogResult dr = CustomMessageBox.Show("Are you sure you want to upload " + items[0].name + "?", "Continue", MessageBoxButtons.YesNo);
|
||||||
if (dr == System.Windows.Forms.DialogResult.Yes)
|
if (dr == System.Windows.Forms.DialogResult.Yes)
|
||||||
{
|
{
|
||||||
update(items[0]);
|
update(items[0]);
|
||||||
|
@ -226,7 +226,7 @@ namespace ArdupilotMega.GCSViews
|
||||||
else if (items.Count == 2 && false)
|
else if (items.Count == 2 && false)
|
||||||
{
|
{
|
||||||
XorPlus select = new XorPlus();
|
XorPlus select = new XorPlus();
|
||||||
MainV2.fixtheme(select);
|
ThemeManager.ApplyThemeTo(select);
|
||||||
select.ShowDialog();
|
select.ShowDialog();
|
||||||
int a = 0;
|
int a = 0;
|
||||||
|
|
||||||
|
@ -239,7 +239,7 @@ namespace ArdupilotMega.GCSViews
|
||||||
{
|
{
|
||||||
if (select.frame == "+" && temp.name.Contains("Plus"))
|
if (select.frame == "+" && temp.name.Contains("Plus"))
|
||||||
{
|
{
|
||||||
DialogResult dr = MessageBox.Show("Are you sure you want to upload " + items[a].name + "?", "Continue", MessageBoxButtons.YesNo);
|
DialogResult dr = CustomMessageBox.Show("Are you sure you want to upload " + items[a].name + "?", "Continue", MessageBoxButtons.YesNo);
|
||||||
if (dr == System.Windows.Forms.DialogResult.Yes)
|
if (dr == System.Windows.Forms.DialogResult.Yes)
|
||||||
{
|
{
|
||||||
update(items[a]);
|
update(items[a]);
|
||||||
|
@ -248,7 +248,7 @@ namespace ArdupilotMega.GCSViews
|
||||||
}
|
}
|
||||||
else if (select.frame == "X" && temp.name.Contains("X"))
|
else if (select.frame == "X" && temp.name.Contains("X"))
|
||||||
{
|
{
|
||||||
DialogResult dr = MessageBox.Show("Are you sure you want to upload " + items[a].name + "?", "Continue", MessageBoxButtons.YesNo);
|
DialogResult dr = CustomMessageBox.Show("Are you sure you want to upload " + items[a].name + "?", "Continue", MessageBoxButtons.YesNo);
|
||||||
if (dr == System.Windows.Forms.DialogResult.Yes)
|
if (dr == System.Windows.Forms.DialogResult.Yes)
|
||||||
{
|
{
|
||||||
update(items[a]);
|
update(items[a]);
|
||||||
|
@ -261,7 +261,7 @@ namespace ArdupilotMega.GCSViews
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
MessageBox.Show("Something has gone wrong, to many firmware choices");
|
CustomMessageBox.Show("Something has gone wrong, to many firmware choices");
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -318,7 +318,7 @@ namespace ArdupilotMega.GCSViews
|
||||||
{
|
{
|
||||||
if (softwares.Count == 0)
|
if (softwares.Count == 0)
|
||||||
{
|
{
|
||||||
MessageBox.Show("No valid options");
|
CustomMessageBox.Show("No valid options");
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -330,7 +330,7 @@ namespace ArdupilotMega.GCSViews
|
||||||
|
|
||||||
if (board == "")
|
if (board == "")
|
||||||
{
|
{
|
||||||
MessageBox.Show("Cant detect your APM version. Please check your cabling");
|
CustomMessageBox.Show("Cant detect your APM version. Please check your cabling");
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -344,9 +344,9 @@ namespace ArdupilotMega.GCSViews
|
||||||
|
|
||||||
if (apmformat_version != -1 && apmformat_version != temp.k_format_version)
|
if (apmformat_version != -1 && apmformat_version != temp.k_format_version)
|
||||||
{
|
{
|
||||||
if (DialogResult.No == MessageBox.Show("Epprom changed, all your setting will be lost during the update,\nDo you wish to continue?", "Epprom format changed (" + apmformat_version + " vs " + temp.k_format_version + ")", MessageBoxButtons.YesNo))
|
if (DialogResult.No == CustomMessageBox.Show("Epprom changed, all your setting will be lost during the update,\nDo you wish to continue?", "Epprom format changed (" + apmformat_version + " vs " + temp.k_format_version + ")", MessageBoxButtons.YesNo))
|
||||||
{
|
{
|
||||||
MessageBox.Show("Please connect and backup your config in the configuration tab.");
|
CustomMessageBox.Show("Please connect and backup your config in the configuration tab.");
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -370,7 +370,7 @@ namespace ArdupilotMega.GCSViews
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
MessageBox.Show("Invalid Board Type");
|
CustomMessageBox.Show("Invalid Board Type");
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -426,7 +426,7 @@ namespace ArdupilotMega.GCSViews
|
||||||
this.Refresh();
|
this.Refresh();
|
||||||
log.Info("Downloaded");
|
log.Info("Downloaded");
|
||||||
}
|
}
|
||||||
catch (Exception ex) { lbl_status.Text = "Failed download"; MessageBox.Show("Failed to download new firmware : " + ex.ToString()); return; }
|
catch (Exception ex) { lbl_status.Text = "Failed download"; CustomMessageBox.Show("Failed to download new firmware : " + ex.ToString()); return; }
|
||||||
|
|
||||||
UploadFlash(Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + @"firmware.hex", board);
|
UploadFlash(Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + @"firmware.hex", board);
|
||||||
}
|
}
|
||||||
|
@ -451,7 +451,7 @@ namespace ArdupilotMega.GCSViews
|
||||||
sr.Dispose();
|
sr.Dispose();
|
||||||
}
|
}
|
||||||
lbl_status.Text = "Failed read HEX";
|
lbl_status.Text = "Failed read HEX";
|
||||||
MessageBox.Show("Failed to read firmware.hex : " + ex.Message);
|
CustomMessageBox.Show("Failed to read firmware.hex : " + ex.Message);
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
ArduinoComms port = new ArduinoSTK();
|
ArduinoComms port = new ArduinoSTK();
|
||||||
|
@ -460,7 +460,7 @@ namespace ArdupilotMega.GCSViews
|
||||||
{
|
{
|
||||||
if (FLASH.Length > 126976)
|
if (FLASH.Length > 126976)
|
||||||
{
|
{
|
||||||
MessageBox.Show("Firmware is to big for a 1280, Please upgrade!!");
|
CustomMessageBox.Show("Firmware is to big for a 1280, Please upgrade!!");
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
//port = new ArduinoSTK();
|
//port = new ArduinoSTK();
|
||||||
|
@ -539,7 +539,7 @@ namespace ArdupilotMega.GCSViews
|
||||||
{
|
{
|
||||||
if (FLASH[s] != flashverify[s])
|
if (FLASH[s] != flashverify[s])
|
||||||
{
|
{
|
||||||
MessageBox.Show("Upload succeeded, but verify failed: exp " + FLASH[s].ToString("X") + " got " + flashverify[s].ToString("X") + " at " + s);
|
CustomMessageBox.Show("Upload succeeded, but verify failed: exp " + FLASH[s].ToString("X") + " got " + flashverify[s].ToString("X") + " at " + s);
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -549,7 +549,7 @@ namespace ArdupilotMega.GCSViews
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
lbl_status.Text = "Failed upload";
|
lbl_status.Text = "Failed upload";
|
||||||
MessageBox.Show("Communication Error - no connection");
|
CustomMessageBox.Show("Communication Error - no connection");
|
||||||
}
|
}
|
||||||
port.Close();
|
port.Close();
|
||||||
|
|
||||||
|
@ -588,7 +588,7 @@ namespace ArdupilotMega.GCSViews
|
||||||
catch (Exception ex)
|
catch (Exception ex)
|
||||||
{
|
{
|
||||||
lbl_status.Text = "Failed upload";
|
lbl_status.Text = "Failed upload";
|
||||||
MessageBox.Show("Check port settings or Port in use? " + ex);
|
CustomMessageBox.Show("Check port settings or Port in use? " + ex);
|
||||||
port.Close();
|
port.Close();
|
||||||
}
|
}
|
||||||
flashing = false;
|
flashing = false;
|
||||||
|
@ -655,7 +655,7 @@ namespace ArdupilotMega.GCSViews
|
||||||
|
|
||||||
if (checksumact != checksum)
|
if (checksumact != checksum)
|
||||||
{
|
{
|
||||||
MessageBox.Show("The hex file loaded is invalid, please try again.");
|
CustomMessageBox.Show("The hex file loaded is invalid, please try again.");
|
||||||
throw new Exception("Checksum Failed - Invalid Hex");
|
throw new Exception("Checksum Failed - Invalid Hex");
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -664,7 +664,7 @@ namespace ArdupilotMega.GCSViews
|
||||||
|
|
||||||
if (!hitend)
|
if (!hitend)
|
||||||
{
|
{
|
||||||
MessageBox.Show("The hex file did no contain an end flag. aborting");
|
CustomMessageBox.Show("The hex file did no contain an end flag. aborting");
|
||||||
throw new Exception("No end flag in file");
|
throw new Exception("No end flag in file");
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -678,14 +678,14 @@ namespace ArdupilotMega.GCSViews
|
||||||
if (flashing == true)
|
if (flashing == true)
|
||||||
{
|
{
|
||||||
e.Cancel = true;
|
e.Cancel = true;
|
||||||
MessageBox.Show("Cant exit while updating");
|
CustomMessageBox.Show("Cant exit while updating");
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
private void BUT_setup_Click(object sender, EventArgs e)
|
private void BUT_setup_Click(object sender, EventArgs e)
|
||||||
{
|
{
|
||||||
Form temp = new Setup.Setup();
|
Form temp = new Setup.Setup();
|
||||||
MainV2.fixtheme(temp);
|
ThemeManager.ApplyThemeTo(temp);
|
||||||
temp.ShowDialog();
|
temp.ShowDialog();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -280,7 +280,7 @@ namespace ArdupilotMega.GCSViews
|
||||||
comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.MAV_DATA_STREAM_RC_CHANNELS, MainV2.cs.raterc); // request rc info
|
comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.MAV_DATA_STREAM_RC_CHANNELS, MainV2.cs.raterc); // request rc info
|
||||||
}
|
}
|
||||||
catch { }
|
catch { }
|
||||||
lastdata = DateTime.Now; // prevent flooding
|
lastdata = DateTime.Now.AddSeconds(12); // prevent flooding
|
||||||
}
|
}
|
||||||
|
|
||||||
if (!MainV2.comPort.logreadmode)
|
if (!MainV2.comPort.logreadmode)
|
||||||
|
@ -781,7 +781,7 @@ namespace ArdupilotMega.GCSViews
|
||||||
Directory.CreateDirectory(Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + @"logs");
|
Directory.CreateDirectory(Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + @"logs");
|
||||||
swlog = new StreamWriter(Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + @"logs" + Path.DirectorySeparatorChar + DateTime.Now.ToString("yyyy-MM-dd hh-mm") + " telem.log");
|
swlog = new StreamWriter(Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + @"logs" + Path.DirectorySeparatorChar + DateTime.Now.ToString("yyyy-MM-dd hh-mm") + " telem.log");
|
||||||
}
|
}
|
||||||
catch { MessageBox.Show("Log creation error"); }
|
catch { CustomMessageBox.Show("Log creation error"); }
|
||||||
}
|
}
|
||||||
|
|
||||||
private void BUTactiondo_Click(object sender, EventArgs e)
|
private void BUTactiondo_Click(object sender, EventArgs e)
|
||||||
|
@ -795,7 +795,7 @@ namespace ArdupilotMega.GCSViews
|
||||||
comPort.doAction((MAVLink.MAV_ACTION)Enum.Parse(typeof(MAVLink.MAV_ACTION), "MAV_ACTION_" + CMB_action.Text));
|
comPort.doAction((MAVLink.MAV_ACTION)Enum.Parse(typeof(MAVLink.MAV_ACTION), "MAV_ACTION_" + CMB_action.Text));
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
catch { MessageBox.Show("The Command failed to execute"); }
|
catch { CustomMessageBox.Show("The Command failed to execute"); }
|
||||||
((Button)sender).Enabled = true;
|
((Button)sender).Enabled = true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -811,7 +811,7 @@ namespace ArdupilotMega.GCSViews
|
||||||
//System.Threading.Thread.Sleep(100);
|
//System.Threading.Thread.Sleep(100);
|
||||||
//comPort.doAction(MAVLink.MAV_ACTION.MAV_ACTION_SET_AUTO); // set auto
|
//comPort.doAction(MAVLink.MAV_ACTION.MAV_ACTION_SET_AUTO); // set auto
|
||||||
}
|
}
|
||||||
catch { MessageBox.Show("The command failed to execute"); }
|
catch { CustomMessageBox.Show("The command failed to execute"); }
|
||||||
((Button)sender).Enabled = true;
|
((Button)sender).Enabled = true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -852,7 +852,7 @@ namespace ArdupilotMega.GCSViews
|
||||||
private void BUT_RAWSensor_Click(object sender, EventArgs e)
|
private void BUT_RAWSensor_Click(object sender, EventArgs e)
|
||||||
{
|
{
|
||||||
Form temp = new RAW_Sensor();
|
Form temp = new RAW_Sensor();
|
||||||
MainV2.fixtheme(temp);
|
ThemeManager.ApplyThemeTo(temp);
|
||||||
temp.Show();
|
temp.Show();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -872,7 +872,7 @@ namespace ArdupilotMega.GCSViews
|
||||||
{
|
{
|
||||||
if (!MainV2.comPort.BaseStream.IsOpen)
|
if (!MainV2.comPort.BaseStream.IsOpen)
|
||||||
{
|
{
|
||||||
MessageBox.Show("Please Connect First");
|
CustomMessageBox.Show("Please Connect First");
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -892,13 +892,13 @@ namespace ArdupilotMega.GCSViews
|
||||||
int intalt = (int)(100 * MainV2.cs.multiplierdist);
|
int intalt = (int)(100 * MainV2.cs.multiplierdist);
|
||||||
if (!int.TryParse(alt, out intalt))
|
if (!int.TryParse(alt, out intalt))
|
||||||
{
|
{
|
||||||
MessageBox.Show("Bad Alt");
|
CustomMessageBox.Show("Bad Alt");
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (gotolocation.Lat == 0 || gotolocation.Lng == 0)
|
if (gotolocation.Lat == 0 || gotolocation.Lng == 0)
|
||||||
{
|
{
|
||||||
MessageBox.Show("Bad Lat/Long");
|
CustomMessageBox.Show("Bad Lat/Long");
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -919,7 +919,7 @@ namespace ArdupilotMega.GCSViews
|
||||||
|
|
||||||
MainV2.givecomport = false;
|
MainV2.givecomport = false;
|
||||||
}
|
}
|
||||||
catch (Exception ex) { MainV2.givecomport = false; MessageBox.Show("Error sending command : " + ex.Message); }
|
catch (Exception ex) { MainV2.givecomport = false; CustomMessageBox.Show("Error sending command : " + ex.Message); }
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -1009,7 +1009,7 @@ namespace ArdupilotMega.GCSViews
|
||||||
tracklog.Minimum = 0;
|
tracklog.Minimum = 0;
|
||||||
tracklog.Maximum = 100;
|
tracklog.Maximum = 100;
|
||||||
}
|
}
|
||||||
catch { MessageBox.Show("Error: Failed to write log file"); }
|
catch { CustomMessageBox.Show("Error: Failed to write log file"); }
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -1112,7 +1112,7 @@ namespace ArdupilotMega.GCSViews
|
||||||
((Button)sender).Enabled = false;
|
((Button)sender).Enabled = false;
|
||||||
comPort.setWPCurrent((ushort)CMB_setwp.SelectedIndex); // set nav to
|
comPort.setWPCurrent((ushort)CMB_setwp.SelectedIndex); // set nav to
|
||||||
}
|
}
|
||||||
catch { MessageBox.Show("The command failed to execute"); }
|
catch { CustomMessageBox.Show("The command failed to execute"); }
|
||||||
((Button)sender).Enabled = true;
|
((Button)sender).Enabled = true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -1143,7 +1143,7 @@ namespace ArdupilotMega.GCSViews
|
||||||
comPort.doAction(MAVLink.MAV_ACTION.MAV_ACTION_SET_AUTO);
|
comPort.doAction(MAVLink.MAV_ACTION.MAV_ACTION_SET_AUTO);
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
catch { MessageBox.Show("The Command failed to execute"); }
|
catch { CustomMessageBox.Show("The Command failed to execute"); }
|
||||||
((Button)sender).Enabled = true;
|
((Button)sender).Enabled = true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -1158,7 +1158,7 @@ namespace ArdupilotMega.GCSViews
|
||||||
comPort.doAction(MAVLink.MAV_ACTION.MAV_ACTION_RETURN);
|
comPort.doAction(MAVLink.MAV_ACTION.MAV_ACTION_RETURN);
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
catch { MessageBox.Show("The Command failed to execute"); }
|
catch { CustomMessageBox.Show("The Command failed to execute"); }
|
||||||
((Button)sender).Enabled = true;
|
((Button)sender).Enabled = true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -1173,7 +1173,7 @@ namespace ArdupilotMega.GCSViews
|
||||||
comPort.doAction(MAVLink.MAV_ACTION.MAV_ACTION_SET_MANUAL);
|
comPort.doAction(MAVLink.MAV_ACTION.MAV_ACTION_SET_MANUAL);
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
catch { MessageBox.Show("The Command failed to execute"); }
|
catch { CustomMessageBox.Show("The Command failed to execute"); }
|
||||||
((Button)sender).Enabled = true;
|
((Button)sender).Enabled = true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -1185,14 +1185,14 @@ namespace ArdupilotMega.GCSViews
|
||||||
}
|
}
|
||||||
|
|
||||||
Form frm = new MavlinkLog();
|
Form frm = new MavlinkLog();
|
||||||
MainV2.fixtheme(frm);
|
ThemeManager.ApplyThemeTo(frm);
|
||||||
frm.ShowDialog();
|
frm.ShowDialog();
|
||||||
}
|
}
|
||||||
|
|
||||||
private void BUT_joystick_Click(object sender, EventArgs e)
|
private void BUT_joystick_Click(object sender, EventArgs e)
|
||||||
{
|
{
|
||||||
Form joy = new JoystickSetup();
|
Form joy = new JoystickSetup();
|
||||||
MainV2.fixtheme(joy);
|
ThemeManager.ApplyThemeTo(joy);
|
||||||
joy.Show();
|
joy.Show();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -1356,7 +1356,7 @@ namespace ArdupilotMega.GCSViews
|
||||||
{
|
{
|
||||||
stopRecordToolStripMenuItem_Click(sender, e);
|
stopRecordToolStripMenuItem_Click(sender, e);
|
||||||
|
|
||||||
MessageBox.Show("Output avi will be saved to the log folder");
|
CustomMessageBox.Show("Output avi will be saved to the log folder");
|
||||||
|
|
||||||
aviwriter = new AviWriter();
|
aviwriter = new AviWriter();
|
||||||
Directory.CreateDirectory(Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + @"logs");
|
Directory.CreateDirectory(Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + @"logs");
|
||||||
|
@ -1480,7 +1480,7 @@ namespace ArdupilotMega.GCSViews
|
||||||
selectform.Width = x + 100;
|
selectform.Width = x + 100;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
MainV2.fixtheme(selectform);
|
ThemeManager.ApplyThemeTo(selectform);
|
||||||
selectform.Show();
|
selectform.Show();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -1552,10 +1552,10 @@ namespace ArdupilotMega.GCSViews
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
MessageBox.Show("Max 10 at a time.");
|
CustomMessageBox.Show("Max 10 at a time.");
|
||||||
((CheckBox)sender).Checked = false;
|
((CheckBox)sender).Checked = false;
|
||||||
}
|
}
|
||||||
MainV2.fixtheme(this);
|
ThemeManager.ApplyThemeTo(this);
|
||||||
|
|
||||||
string selected = "";
|
string selected = "";
|
||||||
try
|
try
|
||||||
|
@ -1635,7 +1635,7 @@ namespace ArdupilotMega.GCSViews
|
||||||
{
|
{
|
||||||
if (!MainV2.comPort.BaseStream.IsOpen)
|
if (!MainV2.comPort.BaseStream.IsOpen)
|
||||||
{
|
{
|
||||||
MessageBox.Show("Please Connect First");
|
CustomMessageBox.Show("Please Connect First");
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -1645,13 +1645,13 @@ namespace ArdupilotMega.GCSViews
|
||||||
int intalt = (int)(100 * MainV2.cs.multiplierdist);
|
int intalt = (int)(100 * MainV2.cs.multiplierdist);
|
||||||
if (!int.TryParse(alt, out intalt))
|
if (!int.TryParse(alt, out intalt))
|
||||||
{
|
{
|
||||||
MessageBox.Show("Bad Alt");
|
CustomMessageBox.Show("Bad Alt");
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (gotolocation.Lat == 0 || gotolocation.Lng == 0)
|
if (gotolocation.Lat == 0 || gotolocation.Lng == 0)
|
||||||
{
|
{
|
||||||
MessageBox.Show("Bad Lat/Long");
|
CustomMessageBox.Show("Bad Lat/Long");
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -1735,7 +1735,7 @@ print 'Roll complete'
|
||||||
|
|
||||||
";
|
";
|
||||||
|
|
||||||
MessageBox.Show("This is Very ALPHA");
|
CustomMessageBox.Show("This is Very ALPHA");
|
||||||
|
|
||||||
Form scriptedit = new Form();
|
Form scriptedit = new Form();
|
||||||
|
|
||||||
|
@ -1757,7 +1757,7 @@ print 'Roll complete'
|
||||||
|
|
||||||
scriptedit.ShowDialog();
|
scriptedit.ShowDialog();
|
||||||
|
|
||||||
if (DialogResult.Yes == MessageBox.Show("Run Script", "Run this script?", MessageBoxButtons.YesNo))
|
if (DialogResult.Yes == CustomMessageBox.Show("Run Script", "Run this script?", MessageBoxButtons.YesNo))
|
||||||
{
|
{
|
||||||
|
|
||||||
Script scr = new Script();
|
Script scr = new Script();
|
||||||
|
|
|
@ -339,7 +339,6 @@
|
||||||
//
|
//
|
||||||
// BUT_write
|
// BUT_write
|
||||||
//
|
//
|
||||||
this.BUT_write.ForeColor = System.Drawing.SystemColors.ControlText;
|
|
||||||
resources.ApplyResources(this.BUT_write, "BUT_write");
|
resources.ApplyResources(this.BUT_write, "BUT_write");
|
||||||
this.BUT_write.Name = "BUT_write";
|
this.BUT_write.Name = "BUT_write";
|
||||||
this.BUT_write.UseVisualStyleBackColor = true;
|
this.BUT_write.UseVisualStyleBackColor = true;
|
||||||
|
@ -347,7 +346,6 @@
|
||||||
//
|
//
|
||||||
// BUT_read
|
// BUT_read
|
||||||
//
|
//
|
||||||
this.BUT_read.ForeColor = System.Drawing.SystemColors.ControlText;
|
|
||||||
resources.ApplyResources(this.BUT_read, "BUT_read");
|
resources.ApplyResources(this.BUT_read, "BUT_read");
|
||||||
this.BUT_read.Name = "BUT_read";
|
this.BUT_read.Name = "BUT_read";
|
||||||
this.BUT_read.UseVisualStyleBackColor = true;
|
this.BUT_read.UseVisualStyleBackColor = true;
|
||||||
|
@ -355,7 +353,6 @@
|
||||||
//
|
//
|
||||||
// SaveFile
|
// SaveFile
|
||||||
//
|
//
|
||||||
this.SaveFile.ForeColor = System.Drawing.SystemColors.ControlText;
|
|
||||||
resources.ApplyResources(this.SaveFile, "SaveFile");
|
resources.ApplyResources(this.SaveFile, "SaveFile");
|
||||||
this.SaveFile.Name = "SaveFile";
|
this.SaveFile.Name = "SaveFile";
|
||||||
this.SaveFile.UseVisualStyleBackColor = true;
|
this.SaveFile.UseVisualStyleBackColor = true;
|
||||||
|
@ -363,7 +360,6 @@
|
||||||
//
|
//
|
||||||
// BUT_loadwpfile
|
// BUT_loadwpfile
|
||||||
//
|
//
|
||||||
this.BUT_loadwpfile.ForeColor = System.Drawing.SystemColors.ControlText;
|
|
||||||
resources.ApplyResources(this.BUT_loadwpfile, "BUT_loadwpfile");
|
resources.ApplyResources(this.BUT_loadwpfile, "BUT_loadwpfile");
|
||||||
this.BUT_loadwpfile.Name = "BUT_loadwpfile";
|
this.BUT_loadwpfile.Name = "BUT_loadwpfile";
|
||||||
this.BUT_loadwpfile.UseVisualStyleBackColor = true;
|
this.BUT_loadwpfile.UseVisualStyleBackColor = true;
|
||||||
|
@ -608,7 +604,6 @@
|
||||||
//
|
//
|
||||||
// button1
|
// button1
|
||||||
//
|
//
|
||||||
this.button1.ForeColor = System.Drawing.SystemColors.ControlText;
|
|
||||||
resources.ApplyResources(this.button1, "button1");
|
resources.ApplyResources(this.button1, "button1");
|
||||||
this.button1.Name = "button1";
|
this.button1.Name = "button1";
|
||||||
this.toolTip1.SetToolTip(this.button1, resources.GetString("button1.ToolTip"));
|
this.toolTip1.SetToolTip(this.button1, resources.GetString("button1.ToolTip"));
|
||||||
|
@ -617,7 +612,6 @@
|
||||||
//
|
//
|
||||||
// BUT_Add
|
// BUT_Add
|
||||||
//
|
//
|
||||||
this.BUT_Add.ForeColor = System.Drawing.SystemColors.ControlText;
|
|
||||||
resources.ApplyResources(this.BUT_Add, "BUT_Add");
|
resources.ApplyResources(this.BUT_Add, "BUT_Add");
|
||||||
this.BUT_Add.Name = "BUT_Add";
|
this.BUT_Add.Name = "BUT_Add";
|
||||||
this.toolTip1.SetToolTip(this.BUT_Add, resources.GetString("BUT_Add.ToolTip"));
|
this.toolTip1.SetToolTip(this.BUT_Add, resources.GetString("BUT_Add.ToolTip"));
|
||||||
|
|
|
@ -98,13 +98,13 @@ namespace ArdupilotMega.GCSViews
|
||||||
|
|
||||||
// if (!hashdefines.ContainsKey("WP_START_BYTE"))
|
// if (!hashdefines.ContainsKey("WP_START_BYTE"))
|
||||||
{
|
{
|
||||||
MessageBox.Show("Your Ardupilot Mega project defines.h is Invalid");
|
CustomMessageBox.Show("Your Ardupilot Mega project defines.h is Invalid");
|
||||||
//return false;
|
//return false;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
catch (Exception)
|
catch (Exception)
|
||||||
{
|
{
|
||||||
MessageBox.Show("Can't open file!");
|
CustomMessageBox.Show("Can't open file!");
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
return true;
|
return true;
|
||||||
|
@ -180,7 +180,7 @@ namespace ArdupilotMega.GCSViews
|
||||||
}
|
}
|
||||||
if (wp_count == byte.MaxValue)
|
if (wp_count == byte.MaxValue)
|
||||||
{
|
{
|
||||||
MessageBox.Show("To many Waypoints!!!");
|
CustomMessageBox.Show("To many Waypoints!!!");
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -200,7 +200,7 @@ namespace ArdupilotMega.GCSViews
|
||||||
}
|
}
|
||||||
catch (Exception ex)
|
catch (Exception ex)
|
||||||
{
|
{
|
||||||
MessageBox.Show("Can't open file! " + ex.ToString());
|
CustomMessageBox.Show("Can't open file! " + ex.ToString());
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
return true;
|
return true;
|
||||||
|
@ -260,7 +260,7 @@ namespace ArdupilotMega.GCSViews
|
||||||
{
|
{
|
||||||
if (selectedrow > Commands.RowCount)
|
if (selectedrow > Commands.RowCount)
|
||||||
{
|
{
|
||||||
MessageBox.Show("Invalid coord, How did you do this?");
|
CustomMessageBox.Show("Invalid coord, How did you do this?");
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
DataGridViewTextBoxCell cell;
|
DataGridViewTextBoxCell cell;
|
||||||
|
@ -286,13 +286,13 @@ namespace ArdupilotMega.GCSViews
|
||||||
|
|
||||||
if (result == 0 || pass == false)
|
if (result == 0 || pass == false)
|
||||||
{
|
{
|
||||||
MessageBox.Show("You must have a home altitude");
|
CustomMessageBox.Show("You must have a home altitude");
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
int results1;
|
int results1;
|
||||||
if (!int.TryParse(TXT_DefaultAlt.Text, out results1))
|
if (!int.TryParse(TXT_DefaultAlt.Text, out results1))
|
||||||
{
|
{
|
||||||
MessageBox.Show("Your default alt is not valid");
|
CustomMessageBox.Show("Your default alt is not valid");
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -332,7 +332,7 @@ namespace ArdupilotMega.GCSViews
|
||||||
|
|
||||||
if (float.Parse(TXT_homealt.Text) + int.Parse(TXT_DefaultAlt.Text) < alt) // calced height is less that GE ground height
|
if (float.Parse(TXT_homealt.Text) + int.Parse(TXT_DefaultAlt.Text) < alt) // calced height is less that GE ground height
|
||||||
{
|
{
|
||||||
MessageBox.Show("Altitude appears to be low!! (you will fly into a hill)\nGoogle Ground height: " + alt + " Meters\nYour height: " + ((float.Parse(TXT_homealt.Text) + int.Parse(TXT_DefaultAlt.Text))) + " Meters");
|
CustomMessageBox.Show("Altitude appears to be low!! (you will fly into a hill)\nGoogle Ground height: " + alt + " Meters\nYour height: " + ((float.Parse(TXT_homealt.Text) + int.Parse(TXT_DefaultAlt.Text))) + " Meters");
|
||||||
cell.Style.BackColor = Color.Red;
|
cell.Style.BackColor = Color.Red;
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
|
@ -346,7 +346,7 @@ namespace ArdupilotMega.GCSViews
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
MessageBox.Show("Invalid Home or wp Alt");
|
CustomMessageBox.Show("Invalid Home or wp Alt");
|
||||||
cell.Style.BackColor = Color.Red;
|
cell.Style.BackColor = Color.Red;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -772,7 +772,7 @@ namespace ArdupilotMega.GCSViews
|
||||||
for (int i = 1; i <= 7; i++)
|
for (int i = 1; i <= 7; i++)
|
||||||
Commands.Columns[i].HeaderText = "setme";
|
Commands.Columns[i].HeaderText = "setme";
|
||||||
}
|
}
|
||||||
catch (Exception ex) { MessageBox.Show(ex.ToString()); }
|
catch (Exception ex) { CustomMessageBox.Show(ex.ToString()); }
|
||||||
}
|
}
|
||||||
|
|
||||||
/// <summary>
|
/// <summary>
|
||||||
|
@ -797,7 +797,7 @@ namespace ArdupilotMega.GCSViews
|
||||||
//Console.WriteLine("editformat " + option + " value " + cmd);
|
//Console.WriteLine("editformat " + option + " value " + cmd);
|
||||||
ChangeColumnHeader(cmd);
|
ChangeColumnHeader(cmd);
|
||||||
}
|
}
|
||||||
catch (Exception ex) { MessageBox.Show(ex.ToString()); }
|
catch (Exception ex) { CustomMessageBox.Show(ex.ToString()); }
|
||||||
}
|
}
|
||||||
|
|
||||||
private void Commands_RowsAdded(object sender, DataGridViewRowsAddedEventArgs e)
|
private void Commands_RowsAdded(object sender, DataGridViewRowsAddedEventArgs e)
|
||||||
|
@ -1179,7 +1179,7 @@ namespace ArdupilotMega.GCSViews
|
||||||
}
|
}
|
||||||
sw.Close();
|
sw.Close();
|
||||||
}
|
}
|
||||||
catch (Exception) { MessageBox.Show("Error writing file"); }
|
catch (Exception) { CustomMessageBox.Show("Error writing file"); }
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -1205,7 +1205,7 @@ namespace ArdupilotMega.GCSViews
|
||||||
frmProgressReporter.DoWork += getWPs;
|
frmProgressReporter.DoWork += getWPs;
|
||||||
frmProgressReporter.UpdateProgressAndStatus(-1, "Receiving WP's");
|
frmProgressReporter.UpdateProgressAndStatus(-1, "Receiving WP's");
|
||||||
|
|
||||||
MainV2.fixtheme(frmProgressReporter);
|
ThemeManager.ApplyThemeTo(frmProgressReporter);
|
||||||
|
|
||||||
frmProgressReporter.RunBackgroundOperationAsync();
|
frmProgressReporter.RunBackgroundOperationAsync();
|
||||||
}
|
}
|
||||||
|
@ -1248,7 +1248,7 @@ namespace ArdupilotMega.GCSViews
|
||||||
|
|
||||||
log.Info("Done");
|
log.Info("Done");
|
||||||
}
|
}
|
||||||
catch (Exception ex) { error = 1; MessageBox.Show("Error : " + ex.ToString()); }
|
catch (Exception ex) { error = 1; CustomMessageBox.Show("Error : " + ex.ToString()); }
|
||||||
try
|
try
|
||||||
{
|
{
|
||||||
this.BeginInvoke((MethodInvoker)delegate()
|
this.BeginInvoke((MethodInvoker)delegate()
|
||||||
|
@ -1282,7 +1282,7 @@ namespace ArdupilotMega.GCSViews
|
||||||
{
|
{
|
||||||
if (CHK_altmode.Checked)
|
if (CHK_altmode.Checked)
|
||||||
{
|
{
|
||||||
if (DialogResult.No == MessageBox.Show("Absolute Alt is ticked are you sure?", "Alt Mode", MessageBoxButtons.YesNo))
|
if (DialogResult.No == CustomMessageBox.Show("Absolute Alt is ticked are you sure?", "Alt Mode", MessageBoxButtons.YesNo))
|
||||||
{
|
{
|
||||||
CHK_altmode.Checked = false;
|
CHK_altmode.Checked = false;
|
||||||
}
|
}
|
||||||
|
@ -1298,7 +1298,7 @@ namespace ArdupilotMega.GCSViews
|
||||||
{
|
{
|
||||||
if (!double.TryParse(Commands[b, a].Value.ToString(), out answer))
|
if (!double.TryParse(Commands[b, a].Value.ToString(), out answer))
|
||||||
{
|
{
|
||||||
MessageBox.Show("There are errors in your mission");
|
CustomMessageBox.Show("There are errors in your mission");
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -1314,7 +1314,7 @@ namespace ArdupilotMega.GCSViews
|
||||||
frmProgressReporter.DoWork += saveWPs;
|
frmProgressReporter.DoWork += saveWPs;
|
||||||
frmProgressReporter.UpdateProgressAndStatus(-1, "Sending WP's");
|
frmProgressReporter.UpdateProgressAndStatus(-1, "Sending WP's");
|
||||||
|
|
||||||
MainV2.fixtheme(frmProgressReporter);
|
ThemeManager.ApplyThemeTo(frmProgressReporter);
|
||||||
|
|
||||||
frmProgressReporter.RunBackgroundOperationAsync();
|
frmProgressReporter.RunBackgroundOperationAsync();
|
||||||
|
|
||||||
|
@ -1427,6 +1427,12 @@ namespace ArdupilotMega.GCSViews
|
||||||
quickadd = true;
|
quickadd = true;
|
||||||
Commands.Rows.Clear();
|
Commands.Rows.Clear();
|
||||||
|
|
||||||
|
if (cmds.Count == 0)
|
||||||
|
{
|
||||||
|
quickadd = false;
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
int i = -1;
|
int i = -1;
|
||||||
foreach (Locationwp temp in cmds)
|
foreach (Locationwp temp in cmds)
|
||||||
{
|
{
|
||||||
|
@ -1495,7 +1501,7 @@ namespace ArdupilotMega.GCSViews
|
||||||
{
|
{
|
||||||
if (cellhome.Value.ToString() != TXT_homelat.Text && cellhome.Value.ToString() != "0")
|
if (cellhome.Value.ToString() != TXT_homelat.Text && cellhome.Value.ToString() != "0")
|
||||||
{
|
{
|
||||||
DialogResult dr = MessageBox.Show("Reset Home to loaded coords", "Reset Home Coords", MessageBoxButtons.YesNo);
|
DialogResult dr = CustomMessageBox.Show("Reset Home to loaded coords", "Reset Home Coords", MessageBoxButtons.YesNo);
|
||||||
|
|
||||||
if (dr == DialogResult.Yes)
|
if (dr == DialogResult.Yes)
|
||||||
{
|
{
|
||||||
|
@ -1627,7 +1633,7 @@ namespace ArdupilotMega.GCSViews
|
||||||
}
|
}
|
||||||
if (isNumber > 127)
|
if (isNumber > 127)
|
||||||
{
|
{
|
||||||
MessageBox.Show("The value can only be between 0 and 127");
|
CustomMessageBox.Show("The value can only be between 0 and 127");
|
||||||
TXT_WPRad.Text = "127";
|
TXT_WPRad.Text = "127";
|
||||||
}
|
}
|
||||||
writeKML();
|
writeKML();
|
||||||
|
@ -1650,7 +1656,7 @@ namespace ArdupilotMega.GCSViews
|
||||||
}
|
}
|
||||||
if (isNumber > 127)
|
if (isNumber > 127)
|
||||||
{
|
{
|
||||||
MessageBox.Show("The value can only be between 0 and 127");
|
CustomMessageBox.Show("The value can only be between 0 and 127");
|
||||||
TXT_loiterrad.Text = "127";
|
TXT_loiterrad.Text = "127";
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -1706,7 +1712,7 @@ namespace ArdupilotMega.GCSViews
|
||||||
writeKML();
|
writeKML();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
catch (Exception) { MessageBox.Show("Row error"); }
|
catch (Exception) { CustomMessageBox.Show("Row error"); }
|
||||||
}
|
}
|
||||||
|
|
||||||
private void Commands_DefaultValuesNeeded(object sender, DataGridViewRowEventArgs e)
|
private void Commands_DefaultValuesNeeded(object sender, DataGridViewRowEventArgs e)
|
||||||
|
@ -1786,7 +1792,7 @@ namespace ArdupilotMega.GCSViews
|
||||||
string header = sr.ReadLine();
|
string header = sr.ReadLine();
|
||||||
if (header == null || !header.Contains("QGC WPL 110"))
|
if (header == null || !header.Contains("QGC WPL 110"))
|
||||||
{
|
{
|
||||||
MessageBox.Show("Invalid Waypoint file");
|
CustomMessageBox.Show("Invalid Waypoint file");
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
while (!error && !sr.EndOfStream)
|
while (!error && !sr.EndOfStream)
|
||||||
|
@ -1833,11 +1839,11 @@ namespace ArdupilotMega.GCSViews
|
||||||
wp_count++;
|
wp_count++;
|
||||||
|
|
||||||
}
|
}
|
||||||
catch { MessageBox.Show("Line invalid\n" + line); }
|
catch { CustomMessageBox.Show("Line invalid\n" + line); }
|
||||||
|
|
||||||
if (wp_count == byte.MaxValue)
|
if (wp_count == byte.MaxValue)
|
||||||
{
|
{
|
||||||
MessageBox.Show("To many Waypoints!!!");
|
CustomMessageBox.Show("To many Waypoints!!!");
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -1853,7 +1859,7 @@ namespace ArdupilotMega.GCSViews
|
||||||
}
|
}
|
||||||
catch (Exception ex)
|
catch (Exception ex)
|
||||||
{
|
{
|
||||||
MessageBox.Show("Can't open file! " + ex.ToString());
|
CustomMessageBox.Show("Can't open file! " + ex.ToString());
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -2246,7 +2252,7 @@ namespace ArdupilotMega.GCSViews
|
||||||
FlightData.mymap.MapType = (MapType)comboBoxMapType.SelectedItem;
|
FlightData.mymap.MapType = (MapType)comboBoxMapType.SelectedItem;
|
||||||
MainV2.config["MapType"] = comboBoxMapType.Text;
|
MainV2.config["MapType"] = comboBoxMapType.Text;
|
||||||
}
|
}
|
||||||
catch { MessageBox.Show("Map change failed. try zomming out first."); }
|
catch { CustomMessageBox.Show("Map change failed. try zomming out first."); }
|
||||||
}
|
}
|
||||||
|
|
||||||
private void Commands_EditingControlShowing(object sender, DataGridViewEditingControlShowingEventArgs e)
|
private void Commands_EditingControlShowing(object sender, DataGridViewEditingControlShowingEventArgs e)
|
||||||
|
@ -2318,7 +2324,7 @@ namespace ArdupilotMega.GCSViews
|
||||||
private void TXT_homelat_Enter(object sender, EventArgs e)
|
private void TXT_homelat_Enter(object sender, EventArgs e)
|
||||||
{
|
{
|
||||||
sethome = true;
|
sethome = true;
|
||||||
MessageBox.Show("Click on the Map to set Home ");
|
CustomMessageBox.Show("Click on the Map to set Home ");
|
||||||
}
|
}
|
||||||
|
|
||||||
private void Planner_Resize(object sender, EventArgs e)
|
private void Planner_Resize(object sender, EventArgs e)
|
||||||
|
@ -2332,14 +2338,14 @@ namespace ArdupilotMega.GCSViews
|
||||||
double homealt;
|
double homealt;
|
||||||
double.TryParse(TXT_homealt.Text, out homealt);
|
double.TryParse(TXT_homealt.Text, out homealt);
|
||||||
Form temp = new ElevationProfile(pointlist, homealt);
|
Form temp = new ElevationProfile(pointlist, homealt);
|
||||||
MainV2.fixtheme(temp);
|
ThemeManager.ApplyThemeTo(temp);
|
||||||
temp.ShowDialog();
|
temp.ShowDialog();
|
||||||
}
|
}
|
||||||
|
|
||||||
private void CHK_altmode_CheckedChanged(object sender, EventArgs e)
|
private void CHK_altmode_CheckedChanged(object sender, EventArgs e)
|
||||||
{
|
{
|
||||||
if (Commands.RowCount > 0 && !quickadd)
|
if (Commands.RowCount > 0 && !quickadd)
|
||||||
MessageBox.Show("You will need to change your altitudes");
|
CustomMessageBox.Show("You will need to change your altitudes");
|
||||||
}
|
}
|
||||||
|
|
||||||
protected override void OnPaint(PaintEventArgs pe)
|
protected override void OnPaint(PaintEventArgs pe)
|
||||||
|
@ -2385,7 +2391,7 @@ namespace ArdupilotMega.GCSViews
|
||||||
RectLatLng area = MainMap.SelectedArea;
|
RectLatLng area = MainMap.SelectedArea;
|
||||||
if (area.IsEmpty)
|
if (area.IsEmpty)
|
||||||
{
|
{
|
||||||
DialogResult res = MessageBox.Show("No ripp area defined, ripp displayed on screen?", "Rip", MessageBoxButtons.YesNo);
|
DialogResult res = CustomMessageBox.Show("No ripp area defined, ripp displayed on screen?", "Rip", MessageBoxButtons.YesNo);
|
||||||
if (res == DialogResult.Yes)
|
if (res == DialogResult.Yes)
|
||||||
{
|
{
|
||||||
area = MainMap.CurrentViewArea;
|
area = MainMap.CurrentViewArea;
|
||||||
|
@ -2394,7 +2400,7 @@ namespace ArdupilotMega.GCSViews
|
||||||
|
|
||||||
if (!area.IsEmpty)
|
if (!area.IsEmpty)
|
||||||
{
|
{
|
||||||
DialogResult res = MessageBox.Show("Ready ripp at Zoom = " + (int)MainMap.Zoom + " ?", "GMap.NET", MessageBoxButtons.YesNo);
|
DialogResult res = CustomMessageBox.Show("Ready ripp at Zoom = " + (int)MainMap.Zoom + " ?", "GMap.NET", MessageBoxButtons.YesNo);
|
||||||
|
|
||||||
for (int i = 1; i <= MainMap.MaxZoom; i++)
|
for (int i = 1; i <= MainMap.MaxZoom; i++)
|
||||||
{
|
{
|
||||||
|
@ -2416,7 +2422,7 @@ namespace ArdupilotMega.GCSViews
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
MessageBox.Show("Select map area holding ALT", "GMap.NET", MessageBoxButtons.OK, MessageBoxIcon.Exclamation);
|
CustomMessageBox.Show("Select map area holding ALT", "GMap.NET", MessageBoxButtons.OK, MessageBoxIcon.Exclamation);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -2479,7 +2485,7 @@ namespace ArdupilotMega.GCSViews
|
||||||
|
|
||||||
if (drawnpolygon == null || drawnpolygon.Points.Count == 0)
|
if (drawnpolygon == null || drawnpolygon.Points.Count == 0)
|
||||||
{
|
{
|
||||||
MessageBox.Show("Right click the map to draw a polygon", "Area", MessageBoxButtons.OK, MessageBoxIcon.Exclamation);
|
CustomMessageBox.Show("Right click the map to draw a polygon", "Area", MessageBoxButtons.OK, MessageBoxIcon.Exclamation);
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
GMapPolygon area = drawnpolygon;
|
GMapPolygon area = drawnpolygon;
|
||||||
|
@ -2514,17 +2520,17 @@ namespace ArdupilotMega.GCSViews
|
||||||
|
|
||||||
if (!double.TryParse(angle, out tryme))
|
if (!double.TryParse(angle, out tryme))
|
||||||
{
|
{
|
||||||
MessageBox.Show("Invalid Angle");
|
CustomMessageBox.Show("Invalid Angle");
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
if (!double.TryParse(alt, out tryme))
|
if (!double.TryParse(alt, out tryme))
|
||||||
{
|
{
|
||||||
MessageBox.Show("Invalid Alt");
|
CustomMessageBox.Show("Invalid Alt");
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
if (!double.TryParse(distance, out tryme))
|
if (!double.TryParse(distance, out tryme))
|
||||||
{
|
{
|
||||||
MessageBox.Show("Invalid Distance");
|
CustomMessageBox.Show("Invalid Distance");
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -2685,7 +2691,7 @@ namespace ArdupilotMega.GCSViews
|
||||||
|
|
||||||
if (Commands.RowCount > 150)
|
if (Commands.RowCount > 150)
|
||||||
{
|
{
|
||||||
MessageBox.Show("Stopping at 150 WP's");
|
CustomMessageBox.Show("Stopping at 150 WP's");
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -2707,7 +2713,7 @@ namespace ArdupilotMega.GCSViews
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
MessageBox.Show("If you're at the field, connect to your APM and wait for GPS lock. Then click 'Home Location' link to set home to your location");
|
CustomMessageBox.Show("If you're at the field, connect to your APM and wait for GPS lock. Then click 'Home Location' link to set home to your location");
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -2765,7 +2771,7 @@ namespace ArdupilotMega.GCSViews
|
||||||
|
|
||||||
polygons.Markers.Add(new GMapMarkerGoogleRed(start));
|
polygons.Markers.Add(new GMapMarkerGoogleRed(start));
|
||||||
MainMap.Invalidate();
|
MainMap.Invalidate();
|
||||||
MessageBox.Show("Distance: " + FormatDistance(MainMap.Manager.GetDistance(startmeasure, start), true) + " AZ: " + (MainMap.Manager.GetBearing(startmeasure, start).ToString("0")));
|
CustomMessageBox.Show("Distance: " + FormatDistance(MainMap.Manager.GetDistance(startmeasure, start), true) + " AZ: " + (MainMap.Manager.GetBearing(startmeasure, start).ToString("0")));
|
||||||
polygons.Polygons.Remove(line);
|
polygons.Polygons.Remove(line);
|
||||||
polygons.Markers.Clear();
|
polygons.Markers.Clear();
|
||||||
startmeasure = new PointLatLng();
|
startmeasure = new PointLatLng();
|
||||||
|
@ -2788,7 +2794,7 @@ namespace ArdupilotMega.GCSViews
|
||||||
{
|
{
|
||||||
if (polygongridmode == false)
|
if (polygongridmode == false)
|
||||||
{
|
{
|
||||||
MessageBox.Show("You will remain in polygon mode until you clear the polygon or create a grid/upload a fence");
|
CustomMessageBox.Show("You will remain in polygon mode until you clear the polygon or create a grid/upload a fence");
|
||||||
}
|
}
|
||||||
|
|
||||||
polygongridmode = true;
|
polygongridmode = true;
|
||||||
|
@ -2903,7 +2909,7 @@ namespace ArdupilotMega.GCSViews
|
||||||
MainMap.Invalidate();
|
MainMap.Invalidate();
|
||||||
}
|
}
|
||||||
catch {
|
catch {
|
||||||
MessageBox.Show("Remove point Failed. Please try again.");
|
CustomMessageBox.Show("Remove point Failed. Please try again.");
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -2952,7 +2958,7 @@ namespace ArdupilotMega.GCSViews
|
||||||
private void BUT_Camera_Click(object sender, EventArgs e)
|
private void BUT_Camera_Click(object sender, EventArgs e)
|
||||||
{
|
{
|
||||||
Camera form = new Camera();
|
Camera form = new Camera();
|
||||||
MainV2.fixtheme(form);
|
ThemeManager.ApplyThemeTo(form);
|
||||||
form.Show();
|
form.Show();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -2975,7 +2981,7 @@ namespace ArdupilotMega.GCSViews
|
||||||
GeoCoderStatusCode status = MainMap.SetCurrentPositionByKeywords(place);
|
GeoCoderStatusCode status = MainMap.SetCurrentPositionByKeywords(place);
|
||||||
if (status != GeoCoderStatusCode.G_GEO_SUCCESS)
|
if (status != GeoCoderStatusCode.G_GEO_SUCCESS)
|
||||||
{
|
{
|
||||||
MessageBox.Show("Google Maps Geocoder can't find: '" + place + "', reason: " + status.ToString(), "GMap.NET", MessageBoxButtons.OK, MessageBoxIcon.Exclamation);
|
CustomMessageBox.Show("Google Maps Geocoder can't find: '" + place + "', reason: " + status.ToString(), "GMap.NET", MessageBoxButtons.OK, MessageBoxIcon.Exclamation);
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
|
@ -3011,7 +3017,7 @@ namespace ArdupilotMega.GCSViews
|
||||||
parser.ElementAdded += parser_ElementAdded;
|
parser.ElementAdded += parser_ElementAdded;
|
||||||
parser.ParseString(kml, true);
|
parser.ParseString(kml, true);
|
||||||
|
|
||||||
if (DialogResult.Yes == MessageBox.Show("Do you want to load this into the flight data screen?", "Load data", MessageBoxButtons.YesNo))
|
if (DialogResult.Yes == CustomMessageBox.Show("Do you want to load this into the flight data screen?", "Load data", MessageBoxButtons.YesNo))
|
||||||
{
|
{
|
||||||
foreach (var temp in kmlpolygons.Polygons)
|
foreach (var temp in kmlpolygons.Polygons)
|
||||||
{
|
{
|
||||||
|
@ -3024,7 +3030,7 @@ namespace ArdupilotMega.GCSViews
|
||||||
}
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
catch (Exception ex) { MessageBox.Show("Bad KML File :" + ex.ToString()); }
|
catch (Exception ex) { CustomMessageBox.Show("Bad KML File :" + ex.ToString()); }
|
||||||
}
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
|
@ -3058,25 +3064,25 @@ namespace ArdupilotMega.GCSViews
|
||||||
//FENCE_TOTAL
|
//FENCE_TOTAL
|
||||||
if (MainV2.comPort.param["FENCE_ACTION"] == null)
|
if (MainV2.comPort.param["FENCE_ACTION"] == null)
|
||||||
{
|
{
|
||||||
MessageBox.Show("Not Supported");
|
CustomMessageBox.Show("Not Supported");
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (drawnpolygon == null)
|
if (drawnpolygon == null)
|
||||||
{
|
{
|
||||||
MessageBox.Show("No polygon to upload");
|
CustomMessageBox.Show("No polygon to upload");
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (geofence.Markers.Count == 0)
|
if (geofence.Markers.Count == 0)
|
||||||
{
|
{
|
||||||
MessageBox.Show("No return location set");
|
CustomMessageBox.Show("No return location set");
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (drawnpolygon.Points.Count == 0)
|
if (drawnpolygon.Points.Count == 0)
|
||||||
{
|
{
|
||||||
MessageBox.Show("No polygon drawn");
|
CustomMessageBox.Show("No polygon drawn");
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -3087,7 +3093,7 @@ namespace ArdupilotMega.GCSViews
|
||||||
// check it
|
// check it
|
||||||
if (!pnpoly(plll.ToArray(), geofence.Markers[0].Position.Lat, geofence.Markers[0].Position.Lng))
|
if (!pnpoly(plll.ToArray(), geofence.Markers[0].Position.Lat, geofence.Markers[0].Position.Lng))
|
||||||
{
|
{
|
||||||
MessageBox.Show("Your return location is outside the polygon");
|
CustomMessageBox.Show("Your return location is outside the polygon");
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -3102,13 +3108,13 @@ namespace ArdupilotMega.GCSViews
|
||||||
|
|
||||||
if (!int.TryParse(minalts, out minalt))
|
if (!int.TryParse(minalts, out minalt))
|
||||||
{
|
{
|
||||||
MessageBox.Show("Bad Min Alt");
|
CustomMessageBox.Show("Bad Min Alt");
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (!int.TryParse(maxalts, out maxalt))
|
if (!int.TryParse(maxalts, out maxalt))
|
||||||
{
|
{
|
||||||
MessageBox.Show("Bad Max Alt");
|
CustomMessageBox.Show("Bad Max Alt");
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -3119,7 +3125,7 @@ namespace ArdupilotMega.GCSViews
|
||||||
}
|
}
|
||||||
catch
|
catch
|
||||||
{
|
{
|
||||||
MessageBox.Show("Failed to set min/max fence alt");
|
CustomMessageBox.Show("Failed to set min/max fence alt");
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -3130,7 +3136,7 @@ namespace ArdupilotMega.GCSViews
|
||||||
}
|
}
|
||||||
catch
|
catch
|
||||||
{
|
{
|
||||||
MessageBox.Show("Failed to set FENCE_ACTION");
|
CustomMessageBox.Show("Failed to set FENCE_ACTION");
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -3186,13 +3192,13 @@ namespace ArdupilotMega.GCSViews
|
||||||
|
|
||||||
if (MainV2.comPort.param["FENCE_ACTION"] == null || MainV2.comPort.param["FENCE_TOTAL"] == null)
|
if (MainV2.comPort.param["FENCE_ACTION"] == null || MainV2.comPort.param["FENCE_TOTAL"] == null)
|
||||||
{
|
{
|
||||||
MessageBox.Show("Not Supported");
|
CustomMessageBox.Show("Not Supported");
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (int.Parse(MainV2.comPort.param["FENCE_TOTAL"].ToString()) <= 1)
|
if (int.Parse(MainV2.comPort.param["FENCE_TOTAL"].ToString()) <= 1)
|
||||||
{
|
{
|
||||||
MessageBox.Show("Nothing to download");
|
CustomMessageBox.Show("Nothing to download");
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -3314,7 +3320,7 @@ namespace ArdupilotMega.GCSViews
|
||||||
{
|
{
|
||||||
if (geofence.Markers.Count == 0)
|
if (geofence.Markers.Count == 0)
|
||||||
{
|
{
|
||||||
MessageBox.Show("Please set a return location");
|
CustomMessageBox.Show("Please set a return location");
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -3356,7 +3362,7 @@ namespace ArdupilotMega.GCSViews
|
||||||
|
|
||||||
sw.Close();
|
sw.Close();
|
||||||
}
|
}
|
||||||
catch { MessageBox.Show("Failed to write fence file"); }
|
catch { CustomMessageBox.Show("Failed to write fence file"); }
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -274,7 +274,7 @@ namespace ArdupilotMega.GCSViews
|
||||||
|
|
||||||
if (MainV2.comPort.BaseStream.IsOpen == false)
|
if (MainV2.comPort.BaseStream.IsOpen == false)
|
||||||
{
|
{
|
||||||
MessageBox.Show("Please connect first");
|
CustomMessageBox.Show("Please connect first");
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -439,9 +439,6 @@ namespace ArdupilotMega.GCSViews
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
FGNetFDM lastfdmdata = new FGNetFDM();
|
FGNetFDM lastfdmdata = new FGNetFDM();
|
||||||
|
|
|
@ -152,7 +152,7 @@ namespace ArdupilotMega.GCSViews
|
||||||
comPort.Write(Encoding.ASCII.GetBytes(cmd + "\r"), 0, cmd.Length + 1);
|
comPort.Write(Encoding.ASCII.GetBytes(cmd + "\r"), 0, cmd.Length + 1);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
catch { MessageBox.Show("Error writing to com port"); }
|
catch { CustomMessageBox.Show("Error writing to com port"); }
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
/*
|
/*
|
||||||
|
@ -293,7 +293,7 @@ namespace ArdupilotMega.GCSViews
|
||||||
private void Logs_Click(object sender, EventArgs e)
|
private void Logs_Click(object sender, EventArgs e)
|
||||||
{
|
{
|
||||||
Form Log = new Log();
|
Form Log = new Log();
|
||||||
MainV2.fixtheme(Log);
|
ThemeManager.ApplyThemeTo(Log);
|
||||||
inlogview = true;
|
inlogview = true;
|
||||||
Log.ShowDialog();
|
Log.ShowDialog();
|
||||||
inlogview = false;
|
inlogview = false;
|
||||||
|
@ -302,7 +302,7 @@ namespace ArdupilotMega.GCSViews
|
||||||
private void BUT_logbrowse_Click(object sender, EventArgs e)
|
private void BUT_logbrowse_Click(object sender, EventArgs e)
|
||||||
{
|
{
|
||||||
Form logbrowse = new LogBrowse();
|
Form logbrowse = new LogBrowse();
|
||||||
MainV2.fixtheme(logbrowse);
|
ThemeManager.ApplyThemeTo(logbrowse);
|
||||||
logbrowse.ShowDialog();
|
logbrowse.ShowDialog();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
|
@ -117,7 +117,7 @@ namespace ArdupilotMega
|
||||||
|
|
||||||
joystick.Acquire();
|
joystick.Acquire();
|
||||||
|
|
||||||
System.Windows.Forms.MessageBox.Show("Please ensure you have calibrated your joystick in Windows first");
|
System.Windows.Forms.CustomMessageBox.Show("Please ensure you have calibrated your joystick in Windows first");
|
||||||
|
|
||||||
joystick.Poll();
|
joystick.Poll();
|
||||||
|
|
||||||
|
@ -133,7 +133,7 @@ namespace ArdupilotMega
|
||||||
values["Slider1"] = obj.GetSlider()[0];
|
values["Slider1"] = obj.GetSlider()[0];
|
||||||
values["Slider2"] = obj.GetSlider()[1];
|
values["Slider2"] = obj.GetSlider()[1];
|
||||||
|
|
||||||
System.Windows.Forms.MessageBox.Show("Please move the joystick axis you want assigned to this function after clicking ok");
|
System.Windows.Forms.CustomMessageBox.Show("Please move the joystick axis you want assigned to this function after clicking ok");
|
||||||
|
|
||||||
DateTime start = DateTime.Now;
|
DateTime start = DateTime.Now;
|
||||||
|
|
||||||
|
@ -178,7 +178,7 @@ namespace ArdupilotMega
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
System.Windows.Forms.MessageBox.Show("No valid option was detected");
|
System.Windows.Forms.CustomMessageBox.Show("No valid option was detected");
|
||||||
|
|
||||||
return joystickaxis.None;
|
return joystickaxis.None;
|
||||||
}
|
}
|
||||||
|
@ -210,7 +210,7 @@ namespace ArdupilotMega
|
||||||
|
|
||||||
joystick.Poll();
|
joystick.Poll();
|
||||||
|
|
||||||
System.Windows.Forms.MessageBox.Show("Please press the joystick button you want assigned to this function after clicking ok");
|
System.Windows.Forms.CustomMessageBox.Show("Please press the joystick button you want assigned to this function after clicking ok");
|
||||||
|
|
||||||
DateTime start = DateTime.Now;
|
DateTime start = DateTime.Now;
|
||||||
|
|
||||||
|
@ -228,7 +228,7 @@ namespace ArdupilotMega
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
System.Windows.Forms.MessageBox.Show("No valid option was detected");
|
System.Windows.Forms.CustomMessageBox.Show("No valid option was detected");
|
||||||
|
|
||||||
return -1;
|
return -1;
|
||||||
}
|
}
|
||||||
|
@ -332,7 +332,7 @@ namespace ArdupilotMega
|
||||||
MainV2.comPort.setMode(mode);
|
MainV2.comPort.setMode(mode);
|
||||||
|
|
||||||
}
|
}
|
||||||
catch { System.Windows.Forms.MessageBox.Show("Failed to change Modes"); }
|
catch { System.Windows.Forms.CustomMessageBox.Show("Failed to change Modes"); }
|
||||||
});
|
});
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
|
@ -34,7 +34,7 @@ namespace ArdupilotMega
|
||||||
CMB_joysticks.Items.Add(device.ProductName);
|
CMB_joysticks.Items.Add(device.ProductName);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
catch { MessageBox.Show("Error geting joystick list: do you have the directx redist installed?"); this.Close(); return; }
|
catch { CustomMessageBox.Show("Error geting joystick list: do you have the directx redist installed?"); this.Close(); return; }
|
||||||
|
|
||||||
if (CMB_joysticks.Items.Count > 0)
|
if (CMB_joysticks.Items.Count > 0)
|
||||||
CMB_joysticks.SelectedIndex = 0;
|
CMB_joysticks.SelectedIndex = 0;
|
||||||
|
@ -134,7 +134,7 @@ namespace ArdupilotMega
|
||||||
{
|
{
|
||||||
joy.setButton(f, int.Parse(this.Controls.Find("cmbbutton" + name, false)[0].Text), this.Controls.Find("cmbaction" + name, false)[0].Text);
|
joy.setButton(f, int.Parse(this.Controls.Find("cmbbutton" + name, false)[0].Text), this.Controls.Find("cmbaction" + name, false)[0].Text);
|
||||||
}
|
}
|
||||||
catch { MessageBox.Show("Set Button "+ name + " Failed"); }
|
catch { CustomMessageBox.Show("Set Button "+ name + " Failed"); }
|
||||||
}
|
}
|
||||||
|
|
||||||
joy.start(CMB_joysticks.Text);
|
joy.start(CMB_joysticks.Text);
|
||||||
|
@ -256,7 +256,7 @@ namespace ArdupilotMega
|
||||||
|
|
||||||
MainV2.joystick = joy;
|
MainV2.joystick = joy;
|
||||||
|
|
||||||
MainV2.fixtheme(this);
|
ThemeManager.ApplyThemeTo(this);
|
||||||
|
|
||||||
CMB_joysticks.SelectedIndex = CMB_joysticks.Items.IndexOf(joy.name);
|
CMB_joysticks.SelectedIndex = CMB_joysticks.Items.IndexOf(joy.name);
|
||||||
}
|
}
|
||||||
|
|
|
@ -77,7 +77,7 @@ namespace ArdupilotMega
|
||||||
catch (Exception ex)
|
catch (Exception ex)
|
||||||
{
|
{
|
||||||
log.Error("Error opening comport", ex);
|
log.Error("Error opening comport", ex);
|
||||||
MessageBox.Show("Error opening comport");
|
CustomMessageBox.Show("Error opening comport");
|
||||||
}
|
}
|
||||||
|
|
||||||
var t11 = new System.Threading.Thread(delegate()
|
var t11 = new System.Threading.Thread(delegate()
|
||||||
|
@ -312,7 +312,7 @@ namespace ArdupilotMega
|
||||||
|
|
||||||
log.Info("exit while");
|
log.Info("exit while");
|
||||||
}
|
}
|
||||||
catch (Exception ex) { MessageBox.Show("Error reading data" + ex.ToString()); }
|
catch (Exception ex) { CustomMessageBox.Show("Error reading data" + ex.ToString()); }
|
||||||
}
|
}
|
||||||
|
|
||||||
string lastline = "";
|
string lastline = "";
|
||||||
|
@ -899,7 +899,7 @@ namespace ArdupilotMega
|
||||||
|
|
||||||
tr.Close();
|
tr.Close();
|
||||||
}
|
}
|
||||||
catch (Exception ex) { MessageBox.Show("Error processing log. Is it still downloading? " + ex.Message); continue; }
|
catch (Exception ex) { CustomMessageBox.Show("Error processing log. Is it still downloading? " + ex.Message); continue; }
|
||||||
|
|
||||||
writeKMLFirstPerson(logfile + ".kml");
|
writeKMLFirstPerson(logfile + ".kml");
|
||||||
|
|
||||||
|
|
|
@ -52,7 +52,7 @@ namespace ArdupilotMega
|
||||||
dataGridView1.DataSource = m_dtCSV;
|
dataGridView1.DataSource = m_dtCSV;
|
||||||
|
|
||||||
}
|
}
|
||||||
catch (Exception ex) { MessageBox.Show("Failed to read File: " + ex.ToString()); }
|
catch (Exception ex) { CustomMessageBox.Show("Failed to read File: " + ex.ToString()); }
|
||||||
|
|
||||||
foreach (DataGridViewColumn column in dataGridView1.Columns)
|
foreach (DataGridViewColumn column in dataGridView1.Columns)
|
||||||
{
|
{
|
||||||
|
@ -256,7 +256,7 @@ namespace ArdupilotMega
|
||||||
{
|
{
|
||||||
if (dataGridView1.RowCount == 0 || dataGridView1.ColumnCount == 0)
|
if (dataGridView1.RowCount == 0 || dataGridView1.ColumnCount == 0)
|
||||||
{
|
{
|
||||||
MessageBox.Show("Please load a valid file");
|
CustomMessageBox.Show("Please load a valid file");
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -267,7 +267,7 @@ namespace ArdupilotMega
|
||||||
|
|
||||||
if (col == 0)
|
if (col == 0)
|
||||||
{
|
{
|
||||||
MessageBox.Show("Please pick another column, Highlight the cell you wish to graph");
|
CustomMessageBox.Show("Please pick another column, Highlight the cell you wish to graph");
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -307,11 +307,11 @@ namespace ArdupilotMega
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
MessageBox.Show("Max of 5");
|
CustomMessageBox.Show("Max of 5");
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
catch { error++; log.Info("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) { CustomMessageBox.Show("There is to much bad data - failing"); break; } }
|
||||||
}
|
}
|
||||||
a++;
|
a++;
|
||||||
}
|
}
|
||||||
|
|
|
@ -146,7 +146,7 @@ namespace ArdupilotMega
|
||||||
frmProgressReporter.DoWork += FrmProgressReporterDoWorkNOParams;
|
frmProgressReporter.DoWork += FrmProgressReporterDoWorkNOParams;
|
||||||
}
|
}
|
||||||
frmProgressReporter.UpdateProgressAndStatus(-1, "Mavlink Connecting...");
|
frmProgressReporter.UpdateProgressAndStatus(-1, "Mavlink Connecting...");
|
||||||
MainV2.fixtheme(frmProgressReporter);
|
ThemeManager.ApplyThemeTo(frmProgressReporter);
|
||||||
|
|
||||||
frmProgressReporter.RunBackgroundOperationAsync();
|
frmProgressReporter.RunBackgroundOperationAsync();
|
||||||
}
|
}
|
||||||
|
@ -184,7 +184,8 @@ namespace ArdupilotMega
|
||||||
|
|
||||||
BaseStream.DiscardInBuffer();
|
BaseStream.DiscardInBuffer();
|
||||||
|
|
||||||
BaseStream.toggleDTR();
|
// removed because of apc220 units
|
||||||
|
//BaseStream.toggleDTR();
|
||||||
|
|
||||||
Thread.Sleep(1000);
|
Thread.Sleep(1000);
|
||||||
}
|
}
|
||||||
|
@ -472,13 +473,6 @@ namespace ArdupilotMega
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
public bool setParam(string paramname, object flag)
|
|
||||||
{
|
|
||||||
int value = (int)(float)param[paramname];
|
|
||||||
|
|
||||||
return setParam(paramname, value | (int)flag);
|
|
||||||
}
|
|
||||||
|
|
||||||
/// <summary>
|
/// <summary>
|
||||||
/// Set parameter on apm
|
/// Set parameter on apm
|
||||||
/// </summary>
|
/// </summary>
|
||||||
|
@ -582,7 +576,7 @@ namespace ArdupilotMega
|
||||||
|
|
||||||
frmProgressReporter.DoWork += FrmProgressReporterGetParams;
|
frmProgressReporter.DoWork += FrmProgressReporterGetParams;
|
||||||
frmProgressReporter.UpdateProgressAndStatus(-1, "Getting Params...");
|
frmProgressReporter.UpdateProgressAndStatus(-1, "Getting Params...");
|
||||||
MainV2.fixtheme(frmProgressReporter);
|
ThemeManager.ApplyThemeTo(frmProgressReporter);
|
||||||
|
|
||||||
frmProgressReporter.RunBackgroundOperationAsync();
|
frmProgressReporter.RunBackgroundOperationAsync();
|
||||||
}
|
}
|
||||||
|
@ -734,6 +728,17 @@ namespace ArdupilotMega
|
||||||
value *= 100.0f;
|
value *= 100.0f;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
else if (paramname.ToUpper().StartsWith("TUNE_"))
|
||||||
|
{
|
||||||
|
if (fromapm)
|
||||||
|
{
|
||||||
|
value /= 1000.0f;
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
value *= 1000.0f;
|
||||||
|
}
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
/// <summary>
|
/// <summary>
|
||||||
|
@ -1440,7 +1445,18 @@ namespace ArdupilotMega
|
||||||
public object DebugPacket(byte[] datin)
|
public object DebugPacket(byte[] datin)
|
||||||
{
|
{
|
||||||
string text = "";
|
string text = "";
|
||||||
return DebugPacket(datin, ref text);
|
return DebugPacket(datin, ref text,true);
|
||||||
|
}
|
||||||
|
|
||||||
|
public object DebugPacket(byte[] datin, bool PrintToConsole)
|
||||||
|
{
|
||||||
|
string text = "";
|
||||||
|
return DebugPacket(datin, ref text, PrintToConsole);
|
||||||
|
}
|
||||||
|
|
||||||
|
public object DebugPacket(byte[] datin, ref string text)
|
||||||
|
{
|
||||||
|
return DebugPacket(datin, ref text, true);
|
||||||
}
|
}
|
||||||
|
|
||||||
/// <summary>
|
/// <summary>
|
||||||
|
@ -1448,7 +1464,7 @@ namespace ArdupilotMega
|
||||||
/// </summary>
|
/// </summary>
|
||||||
/// <param name="datin">packet byte array</param>
|
/// <param name="datin">packet byte array</param>
|
||||||
/// <returns>struct of data</returns>
|
/// <returns>struct of data</returns>
|
||||||
public object DebugPacket(byte[] datin, ref string text)
|
public object DebugPacket(byte[] datin, ref string text, bool PrintToConsole)
|
||||||
{
|
{
|
||||||
string textoutput;
|
string textoutput;
|
||||||
try
|
try
|
||||||
|
@ -1470,34 +1486,46 @@ namespace ArdupilotMega
|
||||||
|
|
||||||
Type test = data.GetType();
|
Type test = data.GetType();
|
||||||
|
|
||||||
textoutput = textoutput + test.Name + " ";
|
if (PrintToConsole)
|
||||||
|
|
||||||
foreach (var field in test.GetFields())
|
|
||||||
{
|
{
|
||||||
// field.Name has the field's name.
|
|
||||||
|
|
||||||
object fieldValue = field.GetValue(data); // Get value
|
textoutput = textoutput + test.Name + " ";
|
||||||
|
|
||||||
if (field.FieldType.IsArray)
|
foreach (var field in test.GetFields())
|
||||||
{
|
{
|
||||||
textoutput = textoutput + field.Name + "=";
|
// field.Name has the field's name.
|
||||||
byte[] crap = (byte[])fieldValue;
|
|
||||||
foreach (byte fiel in crap)
|
object fieldValue = field.GetValue(data); // Get value
|
||||||
|
|
||||||
|
if (field.FieldType.IsArray)
|
||||||
{
|
{
|
||||||
textoutput = textoutput + fiel + ",";
|
textoutput = textoutput + field.Name + "=";
|
||||||
|
byte[] crap = (byte[])fieldValue;
|
||||||
|
foreach (byte fiel in crap)
|
||||||
|
{
|
||||||
|
if (fiel == 0)
|
||||||
|
{
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
textoutput = textoutput + (char)fiel;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
textoutput = textoutput + " ";
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
textoutput = textoutput + field.Name + "=" + fieldValue.ToString() + " ";
|
||||||
}
|
}
|
||||||
textoutput = textoutput + " ";
|
|
||||||
}
|
}
|
||||||
else
|
textoutput = textoutput + " Len:" + datin.Length + "\r\n";
|
||||||
{
|
if (PrintToConsole)
|
||||||
textoutput = textoutput + field.Name + "=" + fieldValue.ToString() + " ";
|
Console.Write(textoutput);
|
||||||
}
|
|
||||||
}
|
|
||||||
textoutput = textoutput + " Len:" + datin.Length + "\r\n";
|
|
||||||
Console.Write(textoutput);
|
|
||||||
|
|
||||||
if (text != null)
|
if (text != null)
|
||||||
text = textoutput;
|
text = textoutput;
|
||||||
|
}
|
||||||
|
|
||||||
return data;
|
return data;
|
||||||
}
|
}
|
||||||
|
@ -1883,7 +1911,7 @@ namespace ArdupilotMega
|
||||||
MainV2.comPort.generatePacket((byte)MAVLink.MAVLINK_MSG_ID_SET_MODE, mode);
|
MainV2.comPort.generatePacket((byte)MAVLink.MAVLINK_MSG_ID_SET_MODE, mode);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
catch { System.Windows.Forms.MessageBox.Show("Failed to change Modes"); }
|
catch { System.Windows.Forms.CustomMessageBox.Show("Failed to change Modes"); }
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
|
@ -5,11 +5,11 @@ using System.Runtime.InteropServices;
|
||||||
|
|
||||||
namespace ArdupilotMega
|
namespace ArdupilotMega
|
||||||
{
|
{
|
||||||
#if !MAVLINK10
|
#if !MAVLINK10
|
||||||
partial class MAVLink
|
partial class MAVLink
|
||||||
{
|
{
|
||||||
public byte[] MAVLINK_MESSAGE_LENGTHS = new byte[] {3, 4, 8, 14, 8, 28, 3, 32, 0, 2, 3, 2, 2, 0, 0, 0, 0, 0, 0, 0, 19, 2, 23, 21, 0, 37, 26, 101, 26, 16, 32, 32, 37, 32, 11, 17, 17, 16, 18, 36, 4, 4, 2, 2, 4, 2, 2, 3, 14, 12, 18, 16, 8, 27, 25, 18, 18, 24, 24, 0, 0, 0, 26, 16, 36, 5, 6, 56, 26, 21, 18, 0, 0, 18, 20, 20, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 18, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 0, 0, 0, 0, 0, 0, 0, 0, 0, 42, 8, 4, 12, 15, 13, 6, 15, 14, 0, 12, 3, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 30, 14, 14, 51, 5};
|
public byte[] MAVLINK_MESSAGE_LENGTHS = new byte[] {3, 4, 8, 14, 8, 28, 3, 32, 0, 2, 3, 2, 2, 0, 0, 0, 0, 0, 0, 0, 19, 2, 23, 21, 0, 37, 26, 101, 26, 16, 32, 32, 37, 32, 11, 17, 17, 16, 18, 36, 4, 4, 2, 2, 4, 2, 2, 3, 14, 12, 18, 16, 8, 27, 25, 18, 18, 24, 24, 0, 0, 0, 26, 16, 36, 5, 6, 56, 26, 21, 18, 0, 0, 18, 20, 20, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 18, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 0, 0, 0, 0, 0, 0, 0, 0, 0, 42, 8, 4, 12, 15, 13, 6, 15, 14, 0, 12, 3, 8, 28, 36, 3, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 30, 14, 14, 51, 5};
|
||||||
public byte[] MAVLINK_MESSAGE_CRCS = new byte[] {72, 39, 190, 92, 191, 217, 104, 119, 0, 219, 60, 186, 10, 0, 0, 0, 0, 0, 0, 0, 89, 159, 162, 121, 0, 149, 222, 110, 179, 136, 66, 126, 185, 147, 112, 252, 162, 215, 229, 128, 9, 106, 101, 213, 4, 229, 21, 214, 215, 14, 206, 50, 157, 126, 108, 213, 95, 5, 127, 0, 0, 0, 57, 126, 130, 119, 193, 191, 236, 158, 143, 0, 0, 104, 123, 131, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 174, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 155, 0, 0, 0, 0, 0, 0, 0, 0, 0, 143, 29, 208, 188, 118, 242, 19, 97, 233, 0, 18, 68, 136, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 178, 224, 60, 106, 7};
|
public byte[] MAVLINK_MESSAGE_CRCS = new byte[] {72, 39, 190, 92, 191, 217, 104, 119, 0, 219, 60, 186, 10, 0, 0, 0, 0, 0, 0, 0, 89, 159, 162, 121, 0, 149, 222, 110, 179, 136, 66, 126, 185, 147, 112, 252, 162, 215, 229, 128, 9, 106, 101, 213, 4, 229, 21, 214, 215, 14, 206, 50, 157, 126, 108, 213, 95, 5, 127, 0, 0, 0, 57, 126, 130, 119, 193, 191, 236, 158, 143, 0, 0, 104, 123, 131, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 174, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 155, 0, 0, 0, 0, 0, 0, 0, 0, 0, 143, 29, 208, 188, 118, 242, 19, 97, 233, 0, 18, 68, 136, 205, 42, 21, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 178, 224, 60, 106, 7};
|
||||||
public enum MAV_MOUNT_MODE
|
public enum MAV_MOUNT_MODE
|
||||||
{
|
{
|
||||||
MAV_MOUNT_MODE_RETRACT=0, /* Load and keep safe position (Roll,Pitch,Yaw) from EEPROM and stop stabilization | */
|
MAV_MOUNT_MODE_RETRACT=0, /* Load and keep safe position (Roll,Pitch,Yaw) from EEPROM and stop stabilization | */
|
||||||
|
@ -78,6 +78,20 @@ namespace ArdupilotMega
|
||||||
};
|
};
|
||||||
|
|
||||||
public const byte MAVLINK_MSG_ID_AP_ADC_LEN = 12;
|
public const byte MAVLINK_MSG_ID_AP_ADC_LEN = 12;
|
||||||
|
public const byte MAVLINK_MSG_ID_DCM = 163;
|
||||||
|
[StructLayout(LayoutKind.Sequential,Pack=1)]
|
||||||
|
public struct __mavlink_dcm_t
|
||||||
|
{
|
||||||
|
public float omegaIx; /// X gyro drift estimate rad/s
|
||||||
|
public float omegaIy; /// Y gyro drift estimate rad/s
|
||||||
|
public float omegaIz; /// Z gyro drift estimate rad/s
|
||||||
|
public float accel_weight; /// average accel_weight
|
||||||
|
public float renorm_val; /// average renormalisation value
|
||||||
|
public float error_rp; /// average error_roll_pitch value
|
||||||
|
public float error_yaw; /// average error_yaw value
|
||||||
|
};
|
||||||
|
|
||||||
|
public const byte MAVLINK_MSG_ID_DCM_LEN = 28;
|
||||||
public const byte MAVLINK_MSG_ID_DIGICAM_CONFIGURE = 154;
|
public const byte MAVLINK_MSG_ID_DIGICAM_CONFIGURE = 154;
|
||||||
[StructLayout(LayoutKind.Sequential,Pack=1)]
|
[StructLayout(LayoutKind.Sequential,Pack=1)]
|
||||||
public struct __mavlink_digicam_configure_t
|
public struct __mavlink_digicam_configure_t
|
||||||
|
@ -166,6 +180,15 @@ namespace ArdupilotMega
|
||||||
};
|
};
|
||||||
|
|
||||||
public const byte MAVLINK_MSG_ID_FENCE_STATUS_LEN = 8;
|
public const byte MAVLINK_MSG_ID_FENCE_STATUS_LEN = 8;
|
||||||
|
public const byte MAVLINK_MSG_ID_HWSTATUS = 165;
|
||||||
|
[StructLayout(LayoutKind.Sequential,Pack=1)]
|
||||||
|
public struct __mavlink_hwstatus_t
|
||||||
|
{
|
||||||
|
public ushort Vcc; /// board voltage (mV)
|
||||||
|
public byte I2Cerr; /// I2C error count
|
||||||
|
};
|
||||||
|
|
||||||
|
public const byte MAVLINK_MSG_ID_HWSTATUS_LEN = 3;
|
||||||
public const byte MAVLINK_MSG_ID_MEMINFO = 152;
|
public const byte MAVLINK_MSG_ID_MEMINFO = 152;
|
||||||
[StructLayout(LayoutKind.Sequential,Pack=1)]
|
[StructLayout(LayoutKind.Sequential,Pack=1)]
|
||||||
public struct __mavlink_meminfo_t
|
public struct __mavlink_meminfo_t
|
||||||
|
@ -244,6 +267,22 @@ namespace ArdupilotMega
|
||||||
};
|
};
|
||||||
|
|
||||||
public const byte MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN = 8;
|
public const byte MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN = 8;
|
||||||
|
public const byte MAVLINK_MSG_ID_SIMSTATE = 164;
|
||||||
|
[StructLayout(LayoutKind.Sequential,Pack=1)]
|
||||||
|
public struct __mavlink_simstate_t
|
||||||
|
{
|
||||||
|
public float roll; /// Roll angle (rad)
|
||||||
|
public float pitch; /// Pitch angle (rad)
|
||||||
|
public float yaw; /// Yaw angle (rad)
|
||||||
|
public float xacc; /// X acceleration m/s/s
|
||||||
|
public float yacc; /// Y acceleration m/s/s
|
||||||
|
public float zacc; /// Z acceleration m/s/s
|
||||||
|
public float xgyro; /// Angular speed around X axis rad/s
|
||||||
|
public float ygyro; /// Angular speed around Y axis rad/s
|
||||||
|
public float zgyro; /// Angular speed around Z axis rad/s
|
||||||
|
};
|
||||||
|
|
||||||
|
public const byte MAVLINK_MSG_ID_SIMSTATE_LEN = 36;
|
||||||
public enum MAV_DATA_STREAM
|
public enum MAV_DATA_STREAM
|
||||||
{
|
{
|
||||||
MAV_DATA_STREAM_ALL=0, /* Enable all data streams | */
|
MAV_DATA_STREAM_ALL=0, /* Enable all data streams | */
|
||||||
|
@ -1305,9 +1344,9 @@ namespace ArdupilotMega
|
||||||
MAV_FRAME_LOCAL_ENU = 4
|
MAV_FRAME_LOCAL_ENU = 4
|
||||||
};
|
};
|
||||||
|
|
||||||
Type[] mavstructs = new Type[] {typeof( __mavlink_heartbeat_t) ,typeof( __mavlink_boot_t) ,null ,typeof( __mavlink_ping_t) ,null ,typeof( __mavlink_change_operator_control_t) ,typeof( __mavlink_change_operator_control_ack_t) ,typeof( __mavlink_auth_key_t) ,null ,typeof( __mavlink_action_ack_t) ,typeof( __mavlink_action_t) ,typeof( __mavlink_set_mode_t) ,typeof( __mavlink_set_nav_mode_t) ,null ,null ,null ,null ,null ,null ,null ,typeof( __mavlink_param_request_read_t) ,typeof( __mavlink_param_request_list_t) ,typeof( __mavlink_param_value_t) ,typeof( __mavlink_param_set_t) ,null ,typeof( __mavlink_gps_raw_int_t) ,typeof( __mavlink_scaled_imu_t) ,typeof( __mavlink_gps_status_t) ,typeof( __mavlink_raw_imu_t) ,typeof( __mavlink_raw_pressure_t) ,typeof( __mavlink_attitude_t) ,typeof( __mavlink_local_position_t) ,typeof( __mavlink_gps_raw_t) ,typeof( __mavlink_global_position_t) ,typeof( __mavlink_sys_status_t) ,typeof( __mavlink_rc_channels_raw_t) ,typeof( __mavlink_rc_channels_scaled_t) ,typeof( __mavlink_servo_output_raw_t) ,typeof( __mavlink_scaled_pressure_t) ,typeof( __mavlink_waypoint_t) ,typeof( __mavlink_waypoint_request_t) ,typeof( __mavlink_waypoint_set_current_t) ,typeof( __mavlink_waypoint_current_t) ,typeof( __mavlink_waypoint_request_list_t) ,typeof( __mavlink_waypoint_count_t) ,typeof( __mavlink_waypoint_clear_all_t) ,typeof( __mavlink_waypoint_reached_t) ,typeof( __mavlink_waypoint_ack_t) ,typeof( __mavlink_gps_set_global_origin_t) ,typeof( __mavlink_gps_local_origin_set_t) ,typeof( __mavlink_local_position_setpoint_set_t) ,typeof( __mavlink_local_position_setpoint_t) ,typeof( __mavlink_control_status_t) ,typeof( __mavlink_safety_set_allowed_area_t) ,typeof( __mavlink_safety_allowed_area_t) ,typeof( __mavlink_set_roll_pitch_yaw_thrust_t) ,typeof( __mavlink_set_roll_pitch_yaw_speed_thrust_t) ,typeof( __mavlink_roll_pitch_yaw_thrust_setpoint_t) ,typeof( __mavlink_roll_pitch_yaw_speed_thrust_setpoint_t) ,null ,null ,null ,typeof( __mavlink_nav_controller_output_t) ,typeof( __mavlink_position_target_t) ,typeof( __mavlink_state_correction_t) ,typeof( __mavlink_set_altitude_t) ,typeof( __mavlink_request_data_stream_t) ,typeof( __mavlink_hil_state_t) ,typeof( __mavlink_hil_controls_t) ,typeof( __mavlink_manual_control_t) ,typeof( __mavlink_rc_channels_override_t) ,null ,null ,typeof( __mavlink_global_position_int_t) ,typeof( __mavlink_vfr_hud_t) ,typeof( __mavlink_command_t) ,typeof( __mavlink_command_ack_t) ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,typeof( __mavlink_optical_flow_t) ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,typeof( __mavlink_object_detection_event_t) ,null ,null ,null ,null ,null ,null ,null ,null ,null ,typeof( __mavlink_sensor_offsets_t) ,typeof( __mavlink_set_mag_offsets_t) ,typeof( __mavlink_meminfo_t) ,typeof( __mavlink_ap_adc_t) ,typeof( __mavlink_digicam_configure_t) ,typeof( __mavlink_digicam_control_t) ,typeof( __mavlink_mount_configure_t) ,typeof( __mavlink_mount_control_t) ,typeof( __mavlink_mount_status_t) ,null ,typeof( __mavlink_fence_point_t) ,typeof( __mavlink_fence_fetch_point_t) ,typeof( __mavlink_fence_status_t) ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,typeof( __mavlink_debug_vect_t) ,typeof( __mavlink_named_value_float_t) ,typeof( __mavlink_named_value_int_t) ,typeof( __mavlink_statustext_t) ,typeof( __mavlink_debug_t) ,null ,};
|
Type[] mavstructs = new Type[] {typeof( __mavlink_heartbeat_t) ,typeof( __mavlink_boot_t) ,null ,typeof( __mavlink_ping_t) ,null ,typeof( __mavlink_change_operator_control_t) ,typeof( __mavlink_change_operator_control_ack_t) ,typeof( __mavlink_auth_key_t) ,null ,typeof( __mavlink_action_ack_t) ,typeof( __mavlink_action_t) ,typeof( __mavlink_set_mode_t) ,typeof( __mavlink_set_nav_mode_t) ,null ,null ,null ,null ,null ,null ,null ,typeof( __mavlink_param_request_read_t) ,typeof( __mavlink_param_request_list_t) ,typeof( __mavlink_param_value_t) ,typeof( __mavlink_param_set_t) ,null ,typeof( __mavlink_gps_raw_int_t) ,typeof( __mavlink_scaled_imu_t) ,typeof( __mavlink_gps_status_t) ,typeof( __mavlink_raw_imu_t) ,typeof( __mavlink_raw_pressure_t) ,typeof( __mavlink_attitude_t) ,typeof( __mavlink_local_position_t) ,typeof( __mavlink_gps_raw_t) ,typeof( __mavlink_global_position_t) ,typeof( __mavlink_sys_status_t) ,typeof( __mavlink_rc_channels_raw_t) ,typeof( __mavlink_rc_channels_scaled_t) ,typeof( __mavlink_servo_output_raw_t) ,typeof( __mavlink_scaled_pressure_t) ,typeof( __mavlink_waypoint_t) ,typeof( __mavlink_waypoint_request_t) ,typeof( __mavlink_waypoint_set_current_t) ,typeof( __mavlink_waypoint_current_t) ,typeof( __mavlink_waypoint_request_list_t) ,typeof( __mavlink_waypoint_count_t) ,typeof( __mavlink_waypoint_clear_all_t) ,typeof( __mavlink_waypoint_reached_t) ,typeof( __mavlink_waypoint_ack_t) ,typeof( __mavlink_gps_set_global_origin_t) ,typeof( __mavlink_gps_local_origin_set_t) ,typeof( __mavlink_local_position_setpoint_set_t) ,typeof( __mavlink_local_position_setpoint_t) ,typeof( __mavlink_control_status_t) ,typeof( __mavlink_safety_set_allowed_area_t) ,typeof( __mavlink_safety_allowed_area_t) ,typeof( __mavlink_set_roll_pitch_yaw_thrust_t) ,typeof( __mavlink_set_roll_pitch_yaw_speed_thrust_t) ,typeof( __mavlink_roll_pitch_yaw_thrust_setpoint_t) ,typeof( __mavlink_roll_pitch_yaw_speed_thrust_setpoint_t) ,null ,null ,null ,typeof( __mavlink_nav_controller_output_t) ,typeof( __mavlink_position_target_t) ,typeof( __mavlink_state_correction_t) ,typeof( __mavlink_set_altitude_t) ,typeof( __mavlink_request_data_stream_t) ,typeof( __mavlink_hil_state_t) ,typeof( __mavlink_hil_controls_t) ,typeof( __mavlink_manual_control_t) ,typeof( __mavlink_rc_channels_override_t) ,null ,null ,typeof( __mavlink_global_position_int_t) ,typeof( __mavlink_vfr_hud_t) ,typeof( __mavlink_command_t) ,typeof( __mavlink_command_ack_t) ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,typeof( __mavlink_optical_flow_t) ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,typeof( __mavlink_object_detection_event_t) ,null ,null ,null ,null ,null ,null ,null ,null ,null ,typeof( __mavlink_sensor_offsets_t) ,typeof( __mavlink_set_mag_offsets_t) ,typeof( __mavlink_meminfo_t) ,typeof( __mavlink_ap_adc_t) ,typeof( __mavlink_digicam_configure_t) ,typeof( __mavlink_digicam_control_t) ,typeof( __mavlink_mount_configure_t) ,typeof( __mavlink_mount_control_t) ,typeof( __mavlink_mount_status_t) ,null ,typeof( __mavlink_fence_point_t) ,typeof( __mavlink_fence_fetch_point_t) ,typeof( __mavlink_fence_status_t) ,typeof( __mavlink_dcm_t) ,typeof( __mavlink_simstate_t) ,typeof( __mavlink_hwstatus_t) ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,null ,typeof( __mavlink_debug_vect_t) ,typeof( __mavlink_named_value_float_t) ,typeof( __mavlink_named_value_int_t) ,typeof( __mavlink_statustext_t) ,typeof( __mavlink_debug_t) ,null ,};
|
||||||
|
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -4,45 +4,25 @@ using System.Linq;
|
||||||
using System.Text;
|
using System.Text;
|
||||||
using System.Windows.Forms;
|
using System.Windows.Forms;
|
||||||
using System.IO;
|
using System.IO;
|
||||||
|
using System.Collections;
|
||||||
|
using netDxf;
|
||||||
|
using netDxf.Entities;
|
||||||
|
using netDxf.Tables;
|
||||||
|
using netDxf.Header;
|
||||||
|
using System.Reflection;
|
||||||
|
using log4net;
|
||||||
|
|
||||||
namespace ArdupilotMega
|
namespace ArdupilotMega
|
||||||
{
|
{
|
||||||
public class MagCalib
|
public class MagCalib
|
||||||
{
|
{
|
||||||
|
private static readonly ILog log = LogManager.GetLogger(MethodBase.GetCurrentMethod().DeclaringType);
|
||||||
|
|
||||||
//alglib.lsfit.
|
/// <summary>
|
||||||
|
/// Self contained process tlog and save/display offsets
|
||||||
public static void doWork()
|
/// </summary>
|
||||||
|
public static void ProcessLog()
|
||||||
{
|
{
|
||||||
/*
|
|
||||||
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();
|
OpenFileDialog openFileDialog1 = new OpenFileDialog();
|
||||||
openFileDialog1.Filter = "*.tlog|*.tlog";
|
openFileDialog1.Filter = "*.tlog|*.tlog";
|
||||||
openFileDialog1.FilterIndex = 2;
|
openFileDialog1.FilterIndex = 2;
|
||||||
|
@ -54,85 +34,244 @@ namespace ArdupilotMega
|
||||||
}
|
}
|
||||||
catch { } // incase dir doesnt exist
|
catch { } // incase dir doesnt exist
|
||||||
|
|
||||||
|
openFileDialog1.FileName = @"C:\Users\hog\Downloads\2012-02-05.log";
|
||||||
|
|
||||||
if (openFileDialog1.ShowDialog() == DialogResult.OK)
|
if (openFileDialog1.ShowDialog() == DialogResult.OK)
|
||||||
{
|
{
|
||||||
foreach (string logfile in openFileDialog1.FileNames)
|
|
||||||
|
double[] ans = getOffsets(openFileDialog1.FileName);
|
||||||
|
|
||||||
|
SaveOffsets(ans);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
/// <summary>
|
||||||
|
/// Processes a tlog to get the offsets - creates dxf of data
|
||||||
|
/// </summary>
|
||||||
|
/// <param name="fn">Filename</param>
|
||||||
|
/// <returns>Offsets</returns>
|
||||||
|
public static double[] getOffsets(string fn)
|
||||||
|
{
|
||||||
|
// based of tridge's work
|
||||||
|
string logfile = fn;
|
||||||
|
|
||||||
|
// old method
|
||||||
|
float minx = 0;
|
||||||
|
float maxx = 0;
|
||||||
|
float miny = 0;
|
||||||
|
float maxy = 0;
|
||||||
|
float minz = 0;
|
||||||
|
float maxz = 0;
|
||||||
|
|
||||||
|
// this is for a dxf
|
||||||
|
Polyline3dVertex vertex;
|
||||||
|
List<Polyline3dVertex> vertexes = new List<Polyline3dVertex>();
|
||||||
|
|
||||||
|
// data storage
|
||||||
|
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>>();
|
||||||
|
|
||||||
|
Hashtable filter = new Hashtable();
|
||||||
|
|
||||||
|
log.Info("Start log: " + DateTime.Now);
|
||||||
|
|
||||||
|
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)
|
||||||
{
|
{
|
||||||
|
byte[] packetraw = mine.readPacket();
|
||||||
|
|
||||||
MAVLink mine = new MAVLink();
|
var packet = mine.DebugPacket(packetraw, false);
|
||||||
mine.logplaybackfile = new BinaryReader(File.Open(logfile, FileMode.Open, FileAccess.Read, FileShare.Read));
|
|
||||||
mine.logreadmode = true;
|
|
||||||
|
|
||||||
mine.packets.Initialize(); // clear
|
// this is for packets we dont know about
|
||||||
|
if (packet == null)
|
||||||
|
continue;
|
||||||
|
|
||||||
// gather data
|
if (packet.GetType() == typeof(MAVLink.__mavlink_sensor_offsets_t))
|
||||||
while (mine.logplaybackfile.BaseStream.Position < mine.logplaybackfile.BaseStream.Length)
|
|
||||||
{
|
{
|
||||||
// bar moves to 100 % in this step
|
offset = new Tuple<float, float, float>(
|
||||||
//progressBar1.Value = (int)((float)mine.logplaybackfile.BaseStream.Position / (float)mine.logplaybackfile.BaseStream.Length * 100.0f / 1.0f);
|
((MAVLink.__mavlink_sensor_offsets_t)packet).mag_ofs_x,
|
||||||
|
((MAVLink.__mavlink_sensor_offsets_t)packet).mag_ofs_y,
|
||||||
|
((MAVLink.__mavlink_sensor_offsets_t)packet).mag_ofs_z);
|
||||||
|
}
|
||||||
|
else if (packet.GetType() == typeof(MAVLink.__mavlink_raw_imu_t))
|
||||||
|
{
|
||||||
|
int div = 20;
|
||||||
|
|
||||||
//progressBar1.Refresh();
|
// fox dxf
|
||||||
//Application.DoEvents();
|
vertex = new Polyline3dVertex(new Vector3f(
|
||||||
|
((MAVLink.__mavlink_raw_imu_t)packet).xmag - offset.Item1,
|
||||||
|
((MAVLink.__mavlink_raw_imu_t)packet).ymag - offset.Item2,
|
||||||
|
((MAVLink.__mavlink_raw_imu_t)packet).zmag - offset.Item3)
|
||||||
|
);
|
||||||
|
vertexes.Add(vertex);
|
||||||
|
|
||||||
byte[] packet = mine.readPacket();
|
|
||||||
|
|
||||||
var pack = mine.DebugPacket(packet);
|
// for old method
|
||||||
|
setMinorMax(((MAVLink.__mavlink_raw_imu_t)packet).xmag - offset.Item1, ref minx, ref maxx);
|
||||||
|
setMinorMax(((MAVLink.__mavlink_raw_imu_t)packet).ymag - offset.Item2, ref miny, ref maxy);
|
||||||
|
setMinorMax(((MAVLink.__mavlink_raw_imu_t)packet).zmag - offset.Item3, ref minz, ref maxz);
|
||||||
|
|
||||||
if (pack.GetType() == typeof(MAVLink.__mavlink_sensor_offsets_t))
|
// for new lease sq
|
||||||
|
string item = (int)(((MAVLink.__mavlink_raw_imu_t)packet).xmag / div) + "," +
|
||||||
|
(int)(((MAVLink.__mavlink_raw_imu_t)packet).ymag / div) + "," +
|
||||||
|
(int)(((MAVLink.__mavlink_raw_imu_t)packet).zmag / div);
|
||||||
|
|
||||||
|
if (filter.ContainsKey(item))
|
||||||
{
|
{
|
||||||
offset = new Tuple<float,float,float>(
|
filter[item] = (int)filter[item] + 1;
|
||||||
((MAVLink.__mavlink_sensor_offsets_t)pack).mag_ofs_x,
|
|
||||||
((MAVLink.__mavlink_sensor_offsets_t)pack).mag_ofs_y,
|
if ((int)filter[item] > 3)
|
||||||
((MAVLink.__mavlink_sensor_offsets_t)pack).mag_ofs_z);
|
continue;
|
||||||
}
|
}
|
||||||
else if (pack.GetType() == typeof(MAVLink.__mavlink_raw_imu_t))
|
else
|
||||||
{
|
{
|
||||||
data.Add(new Tuple<float, float, float>(
|
filter[item] = 1;
|
||||||
((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));
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
data.Add(new Tuple<float, float, float>(
|
||||||
|
((MAVLink.__mavlink_raw_imu_t)packet).xmag - offset.Item1,
|
||||||
|
((MAVLink.__mavlink_raw_imu_t)packet).ymag - offset.Item2,
|
||||||
|
((MAVLink.__mavlink_raw_imu_t)packet).zmag - offset.Item3));
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
//progressBar1.Value = 100;
|
|
||||||
|
|
||||||
mine.logreadmode = false;
|
|
||||||
mine.logplaybackfile.Close();
|
|
||||||
mine.logplaybackfile = null;
|
|
||||||
|
|
||||||
}
|
}
|
||||||
}
|
|
||||||
|
log.Info("Log Processed " + DateTime.Now);
|
||||||
|
|
||||||
|
Console.WriteLine("Extracted " + data.Count + " data points");
|
||||||
|
Console.WriteLine("Current offset: " + offset);
|
||||||
|
|
||||||
|
mine.logreadmode = false;
|
||||||
|
mine.logplaybackfile.Close();
|
||||||
|
mine.logplaybackfile = null;
|
||||||
|
|
||||||
|
double[] x = LeastSq(data);
|
||||||
|
|
||||||
|
System.Console.WriteLine("Old Method {0} {1} {2}", -(maxx + minx) / 2, -(maxy + miny) / 2, -(maxz + minz) / 2);
|
||||||
|
|
||||||
|
log.Info("Least Sq Done " + DateTime.Now);
|
||||||
|
|
||||||
|
// create a dxf for those who want to "see" the calibration
|
||||||
|
DxfDocument dxf = new DxfDocument();
|
||||||
|
|
||||||
|
Polyline3d polyline = new Polyline3d(vertexes, true);
|
||||||
|
polyline.Layer = new Layer("polyline3d");
|
||||||
|
polyline.Layer.Color.Index = 24;
|
||||||
|
dxf.AddEntity(polyline);
|
||||||
|
|
||||||
|
Point pnt = new Point(new Vector3f(-offset.Item1, -offset.Item2, -offset.Item3));
|
||||||
|
pnt.Layer = new Layer("old offset");
|
||||||
|
pnt.Layer.Color.Index = 22;
|
||||||
|
dxf.AddEntity(pnt);
|
||||||
|
|
||||||
|
pnt = new Point(new Vector3f(-(float)x[0], -(float)x[1], -(float)x[2]));
|
||||||
|
pnt.Layer = new Layer("new offset");
|
||||||
|
pnt.Layer.Color.Index = 21;
|
||||||
|
dxf.AddEntity(pnt);
|
||||||
|
|
||||||
|
dxf.Save("magoffset.dxf", DxfVersion.AutoCad2000);
|
||||||
|
|
||||||
|
log.Info("dxf Done " + DateTime.Now);
|
||||||
|
|
||||||
|
Array.Resize<double>(ref x, 3);
|
||||||
|
|
||||||
|
return x;
|
||||||
}
|
}
|
||||||
|
|
||||||
public static List<double> sphere_error(double[,] p, double[] data)
|
/// <summary>
|
||||||
|
/// Does the least sq adjustment to find the center of the sphere
|
||||||
|
/// </summary>
|
||||||
|
/// <param name="data">list of x,y,z data</param>
|
||||||
|
/// <returns>offsets</returns>
|
||||||
|
public static double[] LeastSq(List<Tuple<float, float, float>> data)
|
||||||
{
|
{
|
||||||
double xofs = p[0, 0];
|
double[] x = new double[] { 0, 0, 0, 0 };
|
||||||
double yofs = p[0, 1];
|
double epsg = 0.0000000001;
|
||||||
double zofs = p[0, 2];
|
double epsf = 0;
|
||||||
double r = p[0, 3];
|
double epsx = 0;
|
||||||
List<double> ret = new List<double>();
|
int maxits = 0;
|
||||||
foreach (var d in data)
|
alglib.minlmstate state;
|
||||||
|
alglib.minlmreport rep;
|
||||||
|
|
||||||
|
alglib.minlmcreatev(data.Count, x, 100, out state);
|
||||||
|
alglib.minlmsetcond(state, epsg, epsf, epsx, maxits);
|
||||||
|
alglib.minlmoptimize(state, sphere_error, null, data);
|
||||||
|
alglib.minlmresults(state, out x, out rep);
|
||||||
|
|
||||||
|
log.InfoFormat("{0}", rep.terminationtype);
|
||||||
|
log.InfoFormat("{0}", alglib.ap.format(x, 2));
|
||||||
|
|
||||||
|
return x;
|
||||||
|
}
|
||||||
|
|
||||||
|
/// <summary>
|
||||||
|
/// saves the offests to eeprom, os displays if cant
|
||||||
|
/// </summary>
|
||||||
|
/// <param name="ofs">offsets</param>
|
||||||
|
public static void SaveOffsets(double[] ofs)
|
||||||
|
{
|
||||||
|
if (MainV2.comPort.param.ContainsKey("COMPASS_OFS_X"))
|
||||||
{
|
{
|
||||||
//double x, y, z = d;
|
try
|
||||||
//double err = r - Math.Sqrt(Math.Pow((x + xofs), 2) + Math.Pow((y + yofs), 2) + Math.Pow((z + zofs), 2));
|
{
|
||||||
//ret.Add(err);
|
// disable learning
|
||||||
|
MainV2.comPort.setParam("COMPASS_LEARN", 0);
|
||||||
|
// set values
|
||||||
|
MainV2.comPort.setParam("COMPASS_OFS_X", (float)ofs[0]);
|
||||||
|
MainV2.comPort.setParam("COMPASS_OFS_Y", (float)ofs[1]);
|
||||||
|
MainV2.comPort.setParam("COMPASS_OFS_Z", (float)ofs[2]);
|
||||||
|
}
|
||||||
|
catch {
|
||||||
|
CustomMessageBox.Show("Set Compass offset failed");
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
CustomMessageBox.Show("New offsets are " + ofs[0].ToString("0") + " " + ofs[1].ToString("0") + " " + ofs[2].ToString("0") +"\nThese have been saved for you.", "New Mag Offsets");
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
CustomMessageBox.Show("New offsets are " + ofs[0].ToString("0") + " " + ofs[1].ToString("0") + " " + ofs[2].ToString("0") + "\n\nPlease write these down for manual entry", "New Mag Offsets");
|
||||||
}
|
}
|
||||||
return ret;
|
|
||||||
}
|
}
|
||||||
|
/// <summary>
|
||||||
public static void function_cx_1_func(double[] c, double[] x, ref double func, object obj)
|
/// Min or max finder
|
||||||
|
/// </summary>
|
||||||
|
/// <param name="value">value to process</param>
|
||||||
|
/// <param name="min">current min</param>
|
||||||
|
/// <param name="max">current max</param>
|
||||||
|
private static void setMinorMax(float value, ref float min, ref float max)
|
||||||
{
|
{
|
||||||
// this callback calculates f(c,x)=exp(-c0*sqr(x0))
|
if (value > max)
|
||||||
// where x is a position on X-axis and c is adjustable parameter
|
max = value;
|
||||||
func = System.Math.Exp(-c[0] * x[0] * x[0]);
|
if (value < min)
|
||||||
|
min = value;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
static void sphere_error(double[] xi, double[] fi, object obj)
|
||||||
|
{
|
||||||
|
double xofs = xi[0];
|
||||||
|
double yofs = xi[1];
|
||||||
|
double zofs = xi[2];
|
||||||
|
double r = xi[3];
|
||||||
|
int a = 0;
|
||||||
|
foreach (var d in (List<Tuple<float, float, float>>)obj)
|
||||||
|
{
|
||||||
|
double x = d.Item1;
|
||||||
|
double y = d.Item2;
|
||||||
|
double z = d.Item3;
|
||||||
|
double err = r - Math.Sqrt(Math.Pow((x + xofs), 2) + Math.Pow((y + yofs), 2) + Math.Pow((z + zofs), 2));
|
||||||
|
fi[a] = err;
|
||||||
|
a++;
|
||||||
|
}
|
||||||
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
|
@ -22,6 +22,7 @@ using System.Threading;
|
||||||
using System.Net.Sockets;
|
using System.Net.Sockets;
|
||||||
using IronPython.Hosting;
|
using IronPython.Hosting;
|
||||||
using log4net;
|
using log4net;
|
||||||
|
using ArdupilotMega.Controls;
|
||||||
|
|
||||||
namespace ArdupilotMega
|
namespace ArdupilotMega
|
||||||
{
|
{
|
||||||
|
@ -105,8 +106,7 @@ namespace ArdupilotMega
|
||||||
var t = Type.GetType("Mono.Runtime");
|
var t = Type.GetType("Mono.Runtime");
|
||||||
MONO = (t != null);
|
MONO = (t != null);
|
||||||
|
|
||||||
if (!MONO)
|
talk = new Speech();
|
||||||
talk = new Speech();
|
|
||||||
|
|
||||||
//talk.SpeakAsync("Welcome to APM Planner");
|
//talk.SpeakAsync("Welcome to APM Planner");
|
||||||
|
|
||||||
|
@ -171,7 +171,7 @@ namespace ArdupilotMega
|
||||||
// preload
|
// preload
|
||||||
Python.CreateEngine();
|
Python.CreateEngine();
|
||||||
}
|
}
|
||||||
catch (Exception e) { MessageBox.Show("A Major error has occured : " + e.ToString()); this.Close(); }
|
catch (Exception e) { CustomMessageBox.Show("A Major error has occured : " + e.ToString()); this.Close(); }
|
||||||
|
|
||||||
if (MainV2.config["CHK_GDIPlus"] != null)
|
if (MainV2.config["CHK_GDIPlus"] != null)
|
||||||
GCSViews.FlightData.myhud.UseOpenGL = !bool.Parse(MainV2.config["CHK_GDIPlus"].ToString());
|
GCSViews.FlightData.myhud.UseOpenGL = !bool.Parse(MainV2.config["CHK_GDIPlus"].ToString());
|
||||||
|
@ -205,8 +205,15 @@ namespace ArdupilotMega
|
||||||
|
|
||||||
if (config["speechenable"] != null)
|
if (config["speechenable"] != null)
|
||||||
MainV2.speechenable = bool.Parse(config["speechenable"].ToString());
|
MainV2.speechenable = bool.Parse(config["speechenable"].ToString());
|
||||||
|
|
||||||
|
//int fixme;
|
||||||
|
/*
|
||||||
|
MainV2.cs.rateattitude = 50;
|
||||||
|
MainV2.cs.rateposition = 50;
|
||||||
|
MainV2.cs.ratestatus = 50;
|
||||||
|
MainV2.cs.raterc = 50;
|
||||||
|
MainV2.cs.ratesensors = 50;
|
||||||
|
*/
|
||||||
try
|
try
|
||||||
{
|
{
|
||||||
if (config["TXT_homelat"] != null)
|
if (config["TXT_homelat"] != null)
|
||||||
|
@ -225,7 +232,7 @@ namespace ArdupilotMega
|
||||||
|
|
||||||
if (cs.rateattitude == 0) // initilised to 10, configured above from save
|
if (cs.rateattitude == 0) // initilised to 10, configured above from save
|
||||||
{
|
{
|
||||||
MessageBox.Show("NOTE: your attitude rate is 0, the hud will not work\nChange in Configuration > Planner > Telemetry Rates");
|
CustomMessageBox.Show("NOTE: your attitude rate is 0, the hud will not work\nChange in Configuration > Planner > Telemetry Rates");
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
@ -242,7 +249,7 @@ namespace ArdupilotMega
|
||||||
|
|
||||||
if (Framework < 3.5)
|
if (Framework < 3.5)
|
||||||
{
|
{
|
||||||
MessageBox.Show("This program requires .NET Framework 3.5. You currently have " + Framework);
|
CustomMessageBox.Show("This program requires .NET Framework 3.5. You currently have " + Framework);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -254,37 +261,55 @@ namespace ArdupilotMega
|
||||||
|
|
||||||
private string[] GetPortNames()
|
private string[] GetPortNames()
|
||||||
{
|
{
|
||||||
string[] devs = new string[0];
|
string[] monoDevs = new string[0];
|
||||||
|
|
||||||
|
log.Debug("Getting Comports");
|
||||||
log.Debug("Geting Comports");
|
|
||||||
|
|
||||||
if (MONO)
|
if (MONO)
|
||||||
{
|
{
|
||||||
if (Directory.Exists("/dev/"))
|
if (Directory.Exists("/dev/"))
|
||||||
{
|
{
|
||||||
if (Directory.Exists("/dev/serial/by-id/"))
|
if (Directory.Exists("/dev/serial/by-id/"))
|
||||||
devs = Directory.GetFiles("/dev/serial/by-id/", "*");
|
monoDevs = Directory.GetFiles("/dev/serial/by-id/", "*");
|
||||||
devs = Directory.GetFiles("/dev/", "*ACM*");
|
monoDevs = Directory.GetFiles("/dev/", "*ACM*");
|
||||||
devs = Directory.GetFiles("/dev/", "ttyUSB*");
|
monoDevs = Directory.GetFiles("/dev/", "ttyUSB*");
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
string[] ports = SerialPort.GetPortNames();
|
string[] ports = SerialPort.GetPortNames()
|
||||||
|
.Select(p=>p.TrimEnd())
|
||||||
|
.Select(FixBlueToothPortNameBug)
|
||||||
|
.ToArray();
|
||||||
|
|
||||||
for (int a = 0; a < ports.Length; a++)
|
string[] allPorts = new string[monoDevs.Length + ports.Length];
|
||||||
{
|
|
||||||
ports[a] = ports[a].TrimEnd();
|
|
||||||
}
|
|
||||||
|
|
||||||
string[] all = new string[devs.Length + ports.Length];
|
monoDevs.CopyTo(allPorts, 0);
|
||||||
|
ports.CopyTo(allPorts, monoDevs.Length);
|
||||||
|
|
||||||
devs.CopyTo(all, 0);
|
return allPorts;
|
||||||
ports.CopyTo(all, devs.Length);
|
|
||||||
|
|
||||||
return all;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// .NET bug: sometimes bluetooth ports are enumerated with bogus characters
|
||||||
|
// eg 'COM10' becomes 'COM10c' - one workaround is to remove the non numeric
|
||||||
|
// char. Annoyingly, sometimes a numeric char is added, which means this
|
||||||
|
// does not work in all cases.
|
||||||
|
// See http://connect.microsoft.com/VisualStudio/feedback/details/236183/system-io-ports-serialport-getportnames-error-with-bluetooth
|
||||||
|
private string FixBlueToothPortNameBug(string portName)
|
||||||
|
{
|
||||||
|
if (!portName.StartsWith("COM"))
|
||||||
|
return portName;
|
||||||
|
var newPortName = "COM"; // Start over with "COM"
|
||||||
|
foreach (var portChar in portName.Substring(3).ToCharArray()) // Remove "COM", put the rest in a character array
|
||||||
|
{
|
||||||
|
if (char.IsDigit(portChar))
|
||||||
|
newPortName += portChar.ToString(); // Good character, append to portName
|
||||||
|
else
|
||||||
|
log.WarnFormat("Bad (Non Numeric) character in port name '{0}' - removing", portName);
|
||||||
|
}
|
||||||
|
|
||||||
|
return newPortName;
|
||||||
|
}
|
||||||
|
|
||||||
internal void ScreenShot()
|
internal void ScreenShot()
|
||||||
{
|
{
|
||||||
Rectangle bounds = Screen.GetBounds(Point.Empty);
|
Rectangle bounds = Screen.GetBounds(Point.Empty);
|
||||||
|
@ -296,7 +321,7 @@ namespace ArdupilotMega
|
||||||
}
|
}
|
||||||
string name = "ss" + DateTime.Now.ToString("hhmmss") + ".jpg";
|
string name = "ss" + DateTime.Now.ToString("hhmmss") + ".jpg";
|
||||||
bitmap.Save(Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + name, System.Drawing.Imaging.ImageFormat.Jpeg);
|
bitmap.Save(Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + name, System.Drawing.Imaging.ImageFormat.Jpeg);
|
||||||
MessageBox.Show("Screenshot saved to " + name);
|
CustomMessageBox.Show("Screenshot saved to " + name);
|
||||||
}
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
|
@ -312,174 +337,6 @@ namespace ArdupilotMega
|
||||||
CMB_serialport.Text = oldport;
|
CMB_serialport.Text = oldport;
|
||||||
}
|
}
|
||||||
|
|
||||||
public static void fixtheme(Control temp)
|
|
||||||
{
|
|
||||||
fixtheme(temp, 0);
|
|
||||||
}
|
|
||||||
|
|
||||||
public static void fixtheme(Control temp, int level)
|
|
||||||
{
|
|
||||||
if (level == 0)
|
|
||||||
{
|
|
||||||
temp.BackColor = Color.FromArgb(0x26, 0x27, 0x28);
|
|
||||||
temp.ForeColor = Color.White;// Color.FromArgb(0xe6, 0xe8, 0xea);
|
|
||||||
}
|
|
||||||
//Console.WriteLine(temp.GetType());
|
|
||||||
|
|
||||||
//temp.Font = new Font("Lucida Console", 8.25f);
|
|
||||||
|
|
||||||
foreach (Control ctl in temp.Controls)
|
|
||||||
{
|
|
||||||
if (((Type)ctl.GetType()) == typeof(System.Windows.Forms.Button))
|
|
||||||
{
|
|
||||||
ctl.ForeColor = Color.Black;
|
|
||||||
System.Windows.Forms.Button but = (System.Windows.Forms.Button)ctl;
|
|
||||||
}
|
|
||||||
else if (((Type)ctl.GetType()) == typeof(TextBox))
|
|
||||||
{
|
|
||||||
ctl.BackColor = Color.FromArgb(0x43, 0x44, 0x45);
|
|
||||||
ctl.ForeColor = Color.White;// Color.FromArgb(0xe6, 0xe8, 0xea);
|
|
||||||
TextBox txt = (TextBox)ctl;
|
|
||||||
txt.BorderStyle = BorderStyle.None;
|
|
||||||
}
|
|
||||||
else if (((Type)ctl.GetType()) == typeof(DomainUpDown))
|
|
||||||
{
|
|
||||||
ctl.BackColor = Color.FromArgb(0x43, 0x44, 0x45);
|
|
||||||
ctl.ForeColor = Color.White;// Color.FromArgb(0xe6, 0xe8, 0xea);
|
|
||||||
DomainUpDown txt = (DomainUpDown)ctl;
|
|
||||||
txt.BorderStyle = BorderStyle.None;
|
|
||||||
}
|
|
||||||
else if (((Type)ctl.GetType()) == typeof(GroupBox))
|
|
||||||
{
|
|
||||||
ctl.BackColor = Color.FromArgb(0x26, 0x27, 0x28);
|
|
||||||
ctl.ForeColor = Color.White;// Color.FromArgb(0xe6, 0xe8, 0xea);
|
|
||||||
}
|
|
||||||
else if (((Type)ctl.GetType()) == typeof(ZedGraph.ZedGraphControl))
|
|
||||||
{
|
|
||||||
ZedGraph.ZedGraphControl zg1 = (ZedGraph.ZedGraphControl)ctl;
|
|
||||||
zg1.GraphPane.Chart.Fill = new ZedGraph.Fill(Color.FromArgb(0x1f, 0x1f, 0x20));
|
|
||||||
zg1.GraphPane.Fill = new ZedGraph.Fill(Color.FromArgb(0x37, 0x37, 0x38));
|
|
||||||
|
|
||||||
foreach (ZedGraph.LineItem li in zg1.GraphPane.CurveList)
|
|
||||||
{
|
|
||||||
li.Line.Width = 4;
|
|
||||||
}
|
|
||||||
|
|
||||||
zg1.GraphPane.Title.FontSpec.FontColor = Color.White;
|
|
||||||
|
|
||||||
zg1.GraphPane.XAxis.MajorTic.Color = Color.White;
|
|
||||||
zg1.GraphPane.XAxis.MinorTic.Color = Color.White;
|
|
||||||
zg1.GraphPane.YAxis.MajorTic.Color = Color.White;
|
|
||||||
zg1.GraphPane.YAxis.MinorTic.Color = Color.White;
|
|
||||||
|
|
||||||
zg1.GraphPane.XAxis.MajorGrid.Color = Color.White;
|
|
||||||
zg1.GraphPane.YAxis.MajorGrid.Color = Color.White;
|
|
||||||
|
|
||||||
zg1.GraphPane.YAxis.Scale.FontSpec.FontColor = Color.White;
|
|
||||||
zg1.GraphPane.YAxis.Title.FontSpec.FontColor = Color.White;
|
|
||||||
|
|
||||||
zg1.GraphPane.XAxis.Scale.FontSpec.FontColor = Color.White;
|
|
||||||
zg1.GraphPane.XAxis.Title.FontSpec.FontColor = Color.White;
|
|
||||||
|
|
||||||
zg1.GraphPane.Legend.Fill = new ZedGraph.Fill(Color.FromArgb(0x85, 0x84, 0x83));
|
|
||||||
zg1.GraphPane.Legend.FontSpec.FontColor = Color.White;
|
|
||||||
}
|
|
||||||
else if (((Type)ctl.GetType()) == typeof(BSE.Windows.Forms.Panel) || ((Type)ctl.GetType()) == typeof(System.Windows.Forms.SplitterPanel))
|
|
||||||
{
|
|
||||||
ctl.BackColor = Color.FromArgb(0x26, 0x27, 0x28);
|
|
||||||
ctl.ForeColor = Color.White;// Color.FromArgb(0xe6, 0xe8, 0xea);
|
|
||||||
}
|
|
||||||
else if (((Type)ctl.GetType()) == typeof(Form))
|
|
||||||
{
|
|
||||||
ctl.BackColor = Color.FromArgb(0x26, 0x27, 0x28);
|
|
||||||
ctl.ForeColor = Color.White;// Color.FromArgb(0xe6, 0xe8, 0xea);
|
|
||||||
}
|
|
||||||
else if (((Type)ctl.GetType()) == typeof(RichTextBox))
|
|
||||||
{
|
|
||||||
ctl.BackColor = Color.FromArgb(0x43, 0x44, 0x45);
|
|
||||||
ctl.ForeColor = Color.White;
|
|
||||||
RichTextBox txtr = (RichTextBox)ctl;
|
|
||||||
txtr.BorderStyle = BorderStyle.None;
|
|
||||||
}
|
|
||||||
else if (((Type)ctl.GetType()) == typeof(CheckedListBox))
|
|
||||||
{
|
|
||||||
ctl.BackColor = Color.FromArgb(0x43, 0x44, 0x45);
|
|
||||||
ctl.ForeColor = Color.White;
|
|
||||||
CheckedListBox txtr = (CheckedListBox)ctl;
|
|
||||||
txtr.BorderStyle = BorderStyle.None;
|
|
||||||
}
|
|
||||||
else if (((Type)ctl.GetType()) == typeof(TabPage))
|
|
||||||
{
|
|
||||||
ctl.BackColor = Color.FromArgb(0x26, 0x27, 0x28); //Color.FromArgb(0x43, 0x44, 0x45);
|
|
||||||
ctl.ForeColor = Color.White;
|
|
||||||
TabPage txtr = (TabPage)ctl;
|
|
||||||
txtr.BorderStyle = BorderStyle.None;
|
|
||||||
}
|
|
||||||
else if (((Type)ctl.GetType()) == typeof(TabControl))
|
|
||||||
{
|
|
||||||
ctl.BackColor = Color.FromArgb(0x26, 0x27, 0x28); //Color.FromArgb(0x43, 0x44, 0x45);
|
|
||||||
ctl.ForeColor = Color.White;
|
|
||||||
TabControl txtr = (TabControl)ctl;
|
|
||||||
|
|
||||||
}
|
|
||||||
else if (((Type)ctl.GetType()) == typeof(DataGridView))
|
|
||||||
{
|
|
||||||
ctl.ForeColor = Color.White;
|
|
||||||
DataGridView dgv = (DataGridView)ctl;
|
|
||||||
dgv.EnableHeadersVisualStyles = false;
|
|
||||||
dgv.BorderStyle = BorderStyle.None;
|
|
||||||
dgv.BackgroundColor = Color.FromArgb(0x26, 0x27, 0x28);
|
|
||||||
DataGridViewCellStyle rs = new DataGridViewCellStyle();
|
|
||||||
rs.BackColor = Color.FromArgb(0x43, 0x44, 0x45);
|
|
||||||
rs.ForeColor = Color.White;
|
|
||||||
dgv.RowsDefaultCellStyle = rs;
|
|
||||||
|
|
||||||
DataGridViewCellStyle hs = new DataGridViewCellStyle(dgv.ColumnHeadersDefaultCellStyle);
|
|
||||||
hs.BackColor = Color.FromArgb(0x26, 0x27, 0x28);
|
|
||||||
hs.ForeColor = Color.White;
|
|
||||||
|
|
||||||
dgv.ColumnHeadersDefaultCellStyle = hs;
|
|
||||||
|
|
||||||
dgv.RowHeadersDefaultCellStyle = hs;
|
|
||||||
}
|
|
||||||
else if (((Type)ctl.GetType()) == typeof(ComboBox))
|
|
||||||
{
|
|
||||||
ctl.BackColor = Color.FromArgb(0x43, 0x44, 0x45);
|
|
||||||
ctl.ForeColor = Color.White;
|
|
||||||
ComboBox CMB = (ComboBox)ctl;
|
|
||||||
CMB.FlatStyle = FlatStyle.Flat;
|
|
||||||
}
|
|
||||||
else if (((Type)ctl.GetType()) == typeof(NumericUpDown))
|
|
||||||
{
|
|
||||||
ctl.BackColor = Color.FromArgb(0x43, 0x44, 0x45);
|
|
||||||
ctl.ForeColor = Color.White;
|
|
||||||
}
|
|
||||||
else if (((Type)ctl.GetType()) == typeof(TrackBar))
|
|
||||||
{
|
|
||||||
ctl.BackColor = Color.FromArgb(0x26, 0x27, 0x28);
|
|
||||||
ctl.ForeColor = Color.White;
|
|
||||||
}
|
|
||||||
else if (((Type)ctl.GetType()) == typeof(LinkLabel))
|
|
||||||
{
|
|
||||||
ctl.BackColor = Color.FromArgb(0x26, 0x27, 0x28);
|
|
||||||
ctl.ForeColor = Color.White;
|
|
||||||
LinkLabel LNK = (LinkLabel)ctl;
|
|
||||||
LNK.ActiveLinkColor = Color.White;
|
|
||||||
LNK.LinkColor = Color.White;
|
|
||||||
LNK.VisitedLinkColor = Color.White;
|
|
||||||
|
|
||||||
}
|
|
||||||
else if (((Type)ctl.GetType()) == typeof(HorizontalProgressBar2) ||
|
|
||||||
((Type)ctl.GetType()) == typeof(VerticalProgressBar2))
|
|
||||||
{
|
|
||||||
((HorizontalProgressBar2)ctl).BackgroundColor = Color.FromArgb(0x43, 0x44, 0x45);
|
|
||||||
((HorizontalProgressBar2)ctl).ValueColor = Color.FromArgb(148, 193, 31);
|
|
||||||
}
|
|
||||||
|
|
||||||
if (ctl.Controls.Count > 0)
|
|
||||||
fixtheme(ctl, 1);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
private void MenuFlightData_Click(object sender, EventArgs e)
|
private void MenuFlightData_Click(object sender, EventArgs e)
|
||||||
{
|
{
|
||||||
|
@ -489,7 +346,7 @@ namespace ArdupilotMega
|
||||||
|
|
||||||
UserControl temp = FlightData;
|
UserControl temp = FlightData;
|
||||||
|
|
||||||
fixtheme(temp);
|
ThemeManager.ApplyThemeTo(temp);
|
||||||
|
|
||||||
temp.Anchor = AnchorStyles.Bottom | AnchorStyles.Left | AnchorStyles.Right | AnchorStyles.Top;
|
temp.Anchor = AnchorStyles.Bottom | AnchorStyles.Left | AnchorStyles.Right | AnchorStyles.Top;
|
||||||
|
|
||||||
|
@ -497,10 +354,6 @@ namespace ArdupilotMega
|
||||||
|
|
||||||
temp.Dock = DockStyle.Fill;
|
temp.Dock = DockStyle.Fill;
|
||||||
|
|
||||||
//temp.ForeColor = Color.White;
|
|
||||||
|
|
||||||
//temp.BackColor = Color.FromArgb(0x26, 0x27, 0x28);
|
|
||||||
|
|
||||||
MyView.Controls.Add(temp);
|
MyView.Controls.Add(temp);
|
||||||
|
|
||||||
if (MainV2.config["FlightSplitter"] != null)
|
if (MainV2.config["FlightSplitter"] != null)
|
||||||
|
@ -515,7 +368,7 @@ namespace ArdupilotMega
|
||||||
|
|
||||||
UserControl temp = FlightPlanner;
|
UserControl temp = FlightPlanner;
|
||||||
|
|
||||||
fixtheme(temp);
|
ThemeManager.ApplyThemeTo(temp);
|
||||||
|
|
||||||
temp.Anchor = AnchorStyles.Bottom | AnchorStyles.Left | AnchorStyles.Right | AnchorStyles.Top;
|
temp.Anchor = AnchorStyles.Bottom | AnchorStyles.Left | AnchorStyles.Right | AnchorStyles.Top;
|
||||||
|
|
||||||
|
@ -523,10 +376,6 @@ namespace ArdupilotMega
|
||||||
|
|
||||||
temp.Dock = DockStyle.Fill;
|
temp.Dock = DockStyle.Fill;
|
||||||
|
|
||||||
temp.ForeColor = Color.White;
|
|
||||||
|
|
||||||
temp.BackColor = Color.FromArgb(0x26, 0x27, 0x28);
|
|
||||||
|
|
||||||
MyView.Controls.Add(temp);
|
MyView.Controls.Add(temp);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -550,7 +399,7 @@ namespace ArdupilotMega
|
||||||
|
|
||||||
UserControl temp = Configuration;
|
UserControl temp = Configuration;
|
||||||
|
|
||||||
fixtheme(temp);
|
ThemeManager.ApplyThemeTo(temp);
|
||||||
|
|
||||||
//temp.Anchor = AnchorStyles.Bottom | AnchorStyles.Left | AnchorStyles.Right | AnchorStyles.Top;
|
//temp.Anchor = AnchorStyles.Bottom | AnchorStyles.Left | AnchorStyles.Right | AnchorStyles.Top;
|
||||||
|
|
||||||
|
@ -558,10 +407,6 @@ namespace ArdupilotMega
|
||||||
|
|
||||||
temp.Dock = DockStyle.Fill;
|
temp.Dock = DockStyle.Fill;
|
||||||
|
|
||||||
temp.ForeColor = Color.White;
|
|
||||||
|
|
||||||
temp.BackColor = Color.FromArgb(0x26, 0x27, 0x28);
|
|
||||||
|
|
||||||
temp.Size = MyView.Size;
|
temp.Size = MyView.Size;
|
||||||
|
|
||||||
//temp.Parent = MyView;
|
//temp.Parent = MyView;
|
||||||
|
@ -577,7 +422,7 @@ namespace ArdupilotMega
|
||||||
|
|
||||||
UserControl temp = Simulation;
|
UserControl temp = Simulation;
|
||||||
|
|
||||||
fixtheme(temp);
|
ThemeManager.ApplyThemeTo(temp);
|
||||||
|
|
||||||
temp.Anchor = AnchorStyles.Bottom | AnchorStyles.Left | AnchorStyles.Right | AnchorStyles.Top;
|
temp.Anchor = AnchorStyles.Bottom | AnchorStyles.Left | AnchorStyles.Right | AnchorStyles.Top;
|
||||||
|
|
||||||
|
@ -585,10 +430,6 @@ namespace ArdupilotMega
|
||||||
|
|
||||||
temp.Dock = DockStyle.Fill;
|
temp.Dock = DockStyle.Fill;
|
||||||
|
|
||||||
temp.ForeColor = Color.White;
|
|
||||||
|
|
||||||
temp.BackColor = Color.FromArgb(0x26, 0x27, 0x28);
|
|
||||||
|
|
||||||
MyView.Controls.Add(temp);
|
MyView.Controls.Add(temp);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -600,16 +441,12 @@ namespace ArdupilotMega
|
||||||
|
|
||||||
UserControl temp = Firmware;
|
UserControl temp = Firmware;
|
||||||
|
|
||||||
fixtheme(temp);
|
ThemeManager.ApplyThemeTo(temp);
|
||||||
|
|
||||||
temp.Anchor = AnchorStyles.Bottom | AnchorStyles.Left | AnchorStyles.Right | AnchorStyles.Top;
|
temp.Anchor = AnchorStyles.Bottom | AnchorStyles.Left | AnchorStyles.Right | AnchorStyles.Top;
|
||||||
|
|
||||||
temp.Dock = DockStyle.Fill;
|
temp.Dock = DockStyle.Fill;
|
||||||
|
|
||||||
temp.ForeColor = Color.White;
|
|
||||||
|
|
||||||
temp.BackColor = Color.FromArgb(0x26, 0x27, 0x28);
|
|
||||||
|
|
||||||
MyView.Controls.Add(temp);
|
MyView.Controls.Add(temp);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -640,7 +477,7 @@ namespace ArdupilotMega
|
||||||
|
|
||||||
UserControl temp = Terminal;
|
UserControl temp = Terminal;
|
||||||
|
|
||||||
fixtheme(temp);
|
ThemeManager.ApplyThemeTo(temp);
|
||||||
|
|
||||||
temp.Anchor = AnchorStyles.Bottom | AnchorStyles.Left | AnchorStyles.Right | AnchorStyles.Top;
|
temp.Anchor = AnchorStyles.Bottom | AnchorStyles.Left | AnchorStyles.Right | AnchorStyles.Top;
|
||||||
|
|
||||||
|
@ -648,10 +485,6 @@ namespace ArdupilotMega
|
||||||
|
|
||||||
MyView.Controls.Add(temp);
|
MyView.Controls.Add(temp);
|
||||||
|
|
||||||
temp.ForeColor = Color.White;
|
|
||||||
|
|
||||||
temp.BackColor = Color.FromArgb(0x26, 0x27, 0x28);
|
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
private void MenuConnect_Click(object sender, EventArgs e)
|
private void MenuConnect_Click(object sender, EventArgs e)
|
||||||
|
@ -660,7 +493,7 @@ namespace ArdupilotMega
|
||||||
|
|
||||||
if (comPort.BaseStream.IsOpen && cs.groundspeed > 4)
|
if (comPort.BaseStream.IsOpen && cs.groundspeed > 4)
|
||||||
{
|
{
|
||||||
if (DialogResult.No == MessageBox.Show("Your model is still moving are you sure you want to disconnect?", "Disconnect", MessageBoxButtons.YesNo))
|
if (DialogResult.No == CustomMessageBox.Show("Your model is still moving are you sure you want to disconnect?", "Disconnect", MessageBoxButtons.YesNo))
|
||||||
{
|
{
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
@ -711,11 +544,12 @@ namespace ArdupilotMega
|
||||||
comPort.BaseStream.StopBits = (StopBits)Enum.Parse(typeof(StopBits), "1");
|
comPort.BaseStream.StopBits = (StopBits)Enum.Parse(typeof(StopBits), "1");
|
||||||
comPort.BaseStream.Parity = (Parity)Enum.Parse(typeof(Parity), "None");
|
comPort.BaseStream.Parity = (Parity)Enum.Parse(typeof(Parity), "None");
|
||||||
|
|
||||||
comPort.BaseStream.DtrEnable = false;
|
|
||||||
|
|
||||||
if (config["CHK_resetapmonconnect"] == null || bool.Parse(config["CHK_resetapmonconnect"].ToString()) == true)
|
if (config["CHK_resetapmonconnect"] == null || bool.Parse(config["CHK_resetapmonconnect"].ToString()) == true)
|
||||||
comPort.BaseStream.toggleDTR();
|
comPort.BaseStream.toggleDTR();
|
||||||
|
|
||||||
|
comPort.BaseStream.DtrEnable = false;
|
||||||
|
comPort.BaseStream.RtsEnable = false;
|
||||||
|
|
||||||
try
|
try
|
||||||
{
|
{
|
||||||
if (comPort.logfile != null)
|
if (comPort.logfile != null)
|
||||||
|
@ -723,9 +557,9 @@ namespace ArdupilotMega
|
||||||
try
|
try
|
||||||
{
|
{
|
||||||
Directory.CreateDirectory(Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + @"logs");
|
Directory.CreateDirectory(Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + @"logs");
|
||||||
comPort.logfile = new BinaryWriter(File.Open(Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + @"logs" + Path.DirectorySeparatorChar + DateTime.Now.ToString("yyyy-MM-dd hh-mm-ss") + ".tlog", FileMode.CreateNew));
|
comPort.logfile = new BinaryWriter(File.Open(Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + @"logs" + Path.DirectorySeparatorChar + DateTime.Now.ToString("yyyy-MM-dd hh-mm-ss") + ".tlog", FileMode.CreateNew,FileAccess.ReadWrite,FileShare.Read));
|
||||||
}
|
}
|
||||||
catch { MessageBox.Show("Failed to create log - wont log this session"); } // soft fail
|
catch { CustomMessageBox.Show("Failed to create log - wont log this session"); } // soft fail
|
||||||
|
|
||||||
comPort.BaseStream.PortName = CMB_serialport.Text;
|
comPort.BaseStream.PortName = CMB_serialport.Text;
|
||||||
comPort.Open(true);
|
comPort.Open(true);
|
||||||
|
@ -790,7 +624,7 @@ namespace ArdupilotMega
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
MessageBox.Show("You dont appear to have uploaded a firmware yet,\n\nPlease goto the firmware page and upload one.");
|
CustomMessageBox.Show("You dont appear to have uploaded a firmware yet,\n\nPlease goto the firmware page and upload one.");
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -918,7 +752,7 @@ namespace ArdupilotMega
|
||||||
|
|
||||||
//appconfig.Save();
|
//appconfig.Save();
|
||||||
}
|
}
|
||||||
catch (Exception ex) { MessageBox.Show(ex.ToString()); }
|
catch (Exception ex) { CustomMessageBox.Show(ex.ToString()); }
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
|
@ -1256,6 +1090,9 @@ namespace ArdupilotMega
|
||||||
|
|
||||||
MenuFlightData_Click(sender, e);
|
MenuFlightData_Click(sender, e);
|
||||||
|
|
||||||
|
// for long running tasks using own threads.
|
||||||
|
// for short use threadpool
|
||||||
|
|
||||||
try
|
try
|
||||||
{
|
{
|
||||||
listener = new TcpListener(IPAddress.Any, 56781);
|
listener = new TcpListener(IPAddress.Any, 56781);
|
||||||
|
@ -1270,7 +1107,7 @@ namespace ArdupilotMega
|
||||||
catch (Exception ex)
|
catch (Exception ex)
|
||||||
{
|
{
|
||||||
log.Error("Error starting TCP listener thread: ", ex);
|
log.Error("Error starting TCP listener thread: ", ex);
|
||||||
MessageBox.Show(ex.ToString());
|
CustomMessageBox.Show(ex.ToString());
|
||||||
}
|
}
|
||||||
|
|
||||||
var t12 = new Thread(new ThreadStart(joysticksend))
|
var t12 = new Thread(new ThreadStart(joysticksend))
|
||||||
|
@ -1615,7 +1452,7 @@ namespace ArdupilotMega
|
||||||
|
|
||||||
UserControl temp = new GCSViews.Help();
|
UserControl temp = new GCSViews.Help();
|
||||||
|
|
||||||
fixtheme(temp);
|
ThemeManager.ApplyThemeTo(temp);
|
||||||
|
|
||||||
temp.Anchor = AnchorStyles.Bottom | AnchorStyles.Left | AnchorStyles.Right | AnchorStyles.Top;
|
temp.Anchor = AnchorStyles.Bottom | AnchorStyles.Left | AnchorStyles.Right | AnchorStyles.Top;
|
||||||
|
|
||||||
|
@ -1629,12 +1466,12 @@ namespace ArdupilotMega
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
public static void updatecheck(Label loadinglabel)
|
public static void updatecheck(ProgressReporterDialogue frmProgressReporter)
|
||||||
{
|
{
|
||||||
var baseurl = ConfigurationManager.AppSettings["UpdateLocation"];
|
var baseurl = ConfigurationManager.AppSettings["UpdateLocation"];
|
||||||
try
|
try
|
||||||
{
|
{
|
||||||
bool update = updatecheck(loadinglabel, baseurl, "");
|
bool update = updatecheck(frmProgressReporter, baseurl, "");
|
||||||
var process = new Process();
|
var process = new Process();
|
||||||
string exePath = Path.GetDirectoryName(Application.ExecutablePath);
|
string exePath = Path.GetDirectoryName(Application.ExecutablePath);
|
||||||
if (MONO)
|
if (MONO)
|
||||||
|
@ -1659,23 +1496,26 @@ namespace ArdupilotMega
|
||||||
log.Error("Exception during update", ex);
|
log.Error("Exception during update", ex);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
if (loadinglabel != null)
|
if (frmProgressReporter != null)
|
||||||
UpdateLabel(loadinglabel, "Starting Updater");
|
frmProgressReporter.UpdateProgressAndStatus(-1, "Starting Updater");
|
||||||
log.Info("Starting new process: " + process.StartInfo.FileName + " with " + process.StartInfo.Arguments);
|
log.Info("Starting new process: " + process.StartInfo.FileName + " with " + process.StartInfo.Arguments);
|
||||||
process.Start();
|
process.Start();
|
||||||
log.Info("Quitting existing process");
|
log.Info("Quitting existing process");
|
||||||
try
|
try
|
||||||
{
|
{
|
||||||
Application.Exit();
|
MainV2.instance.BeginInvoke((MethodInvoker)delegate() {
|
||||||
|
Application.Exit();
|
||||||
|
});
|
||||||
}
|
}
|
||||||
catch
|
catch
|
||||||
{
|
{
|
||||||
|
Application.Exit();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
catch (Exception ex)
|
catch (Exception ex)
|
||||||
{
|
{
|
||||||
log.Error("Update Failed", ex);
|
log.Error("Update Failed", ex);
|
||||||
MessageBox.Show("Update Failed " + ex.Message);
|
CustomMessageBox.Show("Update Failed " + ex.Message);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -1719,17 +1559,26 @@ namespace ArdupilotMega
|
||||||
{
|
{
|
||||||
var fi = new FileInfo(path);
|
var fi = new FileInfo(path);
|
||||||
|
|
||||||
log.Info(response.Headers[HttpResponseHeader.ETag]);
|
string CurrentEtag = "";
|
||||||
|
|
||||||
if (fi.Length != response.ContentLength) // && response.Headers[HttpResponseHeader.ETag] != "0")
|
if (File.Exists(path + ".etag"))
|
||||||
{
|
{
|
||||||
using (var sw = new StreamWriter(path + ".etag"))
|
using (Stream fs = File.OpenRead(path + ".etag"))
|
||||||
{
|
{
|
||||||
sw.WriteLine(response.Headers[HttpResponseHeader.ETag]);
|
using (StreamReader sr = new StreamReader(fs))
|
||||||
sw.Close();
|
{
|
||||||
|
CurrentEtag = sr.ReadLine();
|
||||||
|
sr.Close();
|
||||||
|
}
|
||||||
|
fs.Close();
|
||||||
}
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
log.Info("New file Check: " + fi.Length + " vs " + response.ContentLength + " " + response.Headers[HttpResponseHeader.ETag] + " vs " + CurrentEtag);
|
||||||
|
|
||||||
|
if (fi.Length != response.ContentLength || response.Headers[HttpResponseHeader.ETag] != CurrentEtag)
|
||||||
|
{
|
||||||
shouldGetFile = true;
|
shouldGetFile = true;
|
||||||
log.Info("Newer file found: " + path + " " + fi.Length + " vs " + response.ContentLength);
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
|
@ -1743,7 +1592,7 @@ namespace ArdupilotMega
|
||||||
|
|
||||||
if (shouldGetFile)
|
if (shouldGetFile)
|
||||||
{
|
{
|
||||||
var dr = MessageBox.Show("Update Found\n\nDo you wish to update now?", "Update Now", MessageBoxButtons.YesNo);
|
var dr = CustomMessageBox.Show("Update Found\n\nDo you wish to update now?", "Update Now", MessageBoxButtons.YesNo);
|
||||||
if (dr == DialogResult.Yes)
|
if (dr == DialogResult.Yes)
|
||||||
{
|
{
|
||||||
DoUpdate();
|
DoUpdate();
|
||||||
|
@ -1757,46 +1606,28 @@ namespace ArdupilotMega
|
||||||
|
|
||||||
public static void DoUpdate()
|
public static void DoUpdate()
|
||||||
{
|
{
|
||||||
var loading = new Form
|
ProgressReporterDialogue frmProgressReporter = new ProgressReporterDialogue()
|
||||||
{
|
{
|
||||||
|
Text = "Check for Updates",
|
||||||
Width = 400,
|
StartPosition = System.Windows.Forms.FormStartPosition.CenterScreen
|
||||||
Height = 150,
|
|
||||||
StartPosition = FormStartPosition.CenterScreen,
|
|
||||||
TopMost = true,
|
|
||||||
MinimizeBox = false,
|
|
||||||
MaximizeBox = false
|
|
||||||
};
|
};
|
||||||
var resources = new ComponentResourceManager(typeof(MainV2));
|
|
||||||
loading.Icon = ((Icon)(resources.GetObject("$this.Icon")));
|
|
||||||
|
|
||||||
var loadinglabel = new Label
|
ThemeManager.ApplyThemeTo(frmProgressReporter);
|
||||||
{
|
|
||||||
Location = new System.Drawing.Point(50, 40),
|
|
||||||
Name = "load",
|
|
||||||
AutoSize = true,
|
|
||||||
Text = "Checking...",
|
|
||||||
Size = new System.Drawing.Size(100, 20)
|
|
||||||
};
|
|
||||||
|
|
||||||
loading.Controls.Add(loadinglabel);
|
frmProgressReporter.DoWork += new Controls.ProgressReporterDialogue.DoWorkEventHandler(frmProgressReporter_DoWork);
|
||||||
loading.Show();
|
|
||||||
|
|
||||||
try
|
frmProgressReporter.UpdateProgressAndStatus(-1, "Checking for Updates");
|
||||||
{
|
|
||||||
MainV2.updatecheck(loadinglabel);
|
frmProgressReporter.RunBackgroundOperationAsync();
|
||||||
}
|
|
||||||
catch (Exception ex)
|
|
||||||
{
|
|
||||||
log.Error("Error in updatecheck", ex);
|
|
||||||
}
|
|
||||||
//);
|
|
||||||
//t12.Name = "Update check thread";
|
|
||||||
//t12.Start();
|
|
||||||
//MainV2.threads.Add(t12);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
private static bool updatecheck(Label loadinglabel, string baseurl, string subdir)
|
static void frmProgressReporter_DoWork(object sender, Controls.ProgressWorkerEventArgs e)
|
||||||
|
{
|
||||||
|
((ProgressReporterDialogue)sender).UpdateProgressAndStatus(-1, "Getting Base URL");
|
||||||
|
MainV2.updatecheck((ProgressReporterDialogue)sender);
|
||||||
|
}
|
||||||
|
|
||||||
|
private static bool updatecheck(ProgressReporterDialogue frmProgressReporter, string baseurl, string subdir)
|
||||||
{
|
{
|
||||||
bool update = false;
|
bool update = false;
|
||||||
List<string> files = new List<string>();
|
List<string> files = new List<string>();
|
||||||
|
@ -1845,24 +1676,30 @@ namespace ArdupilotMega
|
||||||
Directory.CreateDirectory(dir);
|
Directory.CreateDirectory(dir);
|
||||||
foreach (string file in files)
|
foreach (string file in files)
|
||||||
{
|
{
|
||||||
|
if (frmProgressReporter.doWorkArgs.CancelRequested)
|
||||||
|
{
|
||||||
|
frmProgressReporter.doWorkArgs.CancelAcknowledged = true;
|
||||||
|
throw new Exception("Cancel");
|
||||||
|
}
|
||||||
|
|
||||||
if (file.Equals("/"))
|
if (file.Equals("/"))
|
||||||
{
|
{
|
||||||
continue;
|
continue;
|
||||||
}
|
}
|
||||||
if (file.EndsWith("/"))
|
if (file.EndsWith("/"))
|
||||||
{
|
{
|
||||||
update = updatecheck(loadinglabel, baseurl + file, subdir.Replace('/', Path.DirectorySeparatorChar) + file) && update;
|
update = updatecheck(frmProgressReporter, baseurl + file, subdir.Replace('/', Path.DirectorySeparatorChar) + file) && update;
|
||||||
continue;
|
continue;
|
||||||
}
|
}
|
||||||
if (loadinglabel != null)
|
if (frmProgressReporter != null)
|
||||||
UpdateLabel(loadinglabel, "Checking " + file);
|
frmProgressReporter.UpdateProgressAndStatus(-1, "Checking " + file);
|
||||||
|
|
||||||
string path = Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + subdir + file;
|
string path = Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + subdir + file;
|
||||||
|
|
||||||
|
|
||||||
// Create a request using a URL that can receive a post.
|
// Create a request using a URL that can receive a post.
|
||||||
request = WebRequest.Create(baseurl + file);
|
request = WebRequest.Create(baseurl + file);
|
||||||
Console.Write(baseurl + file + " ");
|
log.Info(baseurl + file + " ");
|
||||||
// Set the Method property of the request to POST.
|
// Set the Method property of the request to POST.
|
||||||
request.Method = "HEAD";
|
request.Method = "HEAD";
|
||||||
|
|
||||||
|
@ -1876,26 +1713,44 @@ namespace ArdupilotMega
|
||||||
//dataStream = response.GetResponseStream();
|
//dataStream = response.GetResponseStream();
|
||||||
// Open the stream using a StreamReader for easy access.
|
// Open the stream using a StreamReader for easy access.
|
||||||
|
|
||||||
bool getfile = false;
|
bool updateThisFile = false;
|
||||||
|
|
||||||
if (File.Exists(path))
|
if (File.Exists(path))
|
||||||
{
|
{
|
||||||
FileInfo fi = new FileInfo(path);
|
FileInfo fi = new FileInfo(path);
|
||||||
|
|
||||||
log.Info(response.Headers[HttpResponseHeader.ETag]);
|
//log.Info(response.Headers[HttpResponseHeader.ETag]);
|
||||||
|
string CurrentEtag = "";
|
||||||
|
|
||||||
if (fi.Length != response.ContentLength) // && response.Headers[HttpResponseHeader.ETag] != "0")
|
if (File.Exists(path + ".etag"))
|
||||||
{
|
{
|
||||||
StreamWriter sw = new StreamWriter(path + ".etag");
|
using (Stream fs = File.OpenRead(path + ".etag"))
|
||||||
sw.WriteLine(response.Headers[HttpResponseHeader.ETag]);
|
{
|
||||||
sw.Close();
|
using (StreamReader sr = new StreamReader(fs))
|
||||||
getfile = true;
|
{
|
||||||
|
CurrentEtag = sr.ReadLine();
|
||||||
|
sr.Close();
|
||||||
|
}
|
||||||
|
fs.Close();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
log.Debug("New file Check: " + fi.Length + " vs " + response.ContentLength + " " + response.Headers[HttpResponseHeader.ETag] + " vs " + CurrentEtag);
|
||||||
|
|
||||||
|
if (fi.Length != response.ContentLength || response.Headers[HttpResponseHeader.ETag] != CurrentEtag)
|
||||||
|
{
|
||||||
|
using (StreamWriter sw = new StreamWriter(path + ".etag"))
|
||||||
|
{
|
||||||
|
sw.WriteLine(response.Headers[HttpResponseHeader.ETag]);
|
||||||
|
sw.Close();
|
||||||
|
}
|
||||||
|
updateThisFile = true;
|
||||||
log.Info("NEW FILE " + file);
|
log.Info("NEW FILE " + file);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
getfile = true;
|
updateThisFile = true;
|
||||||
log.Info("NEW FILE " + file);
|
log.Info("NEW FILE " + file);
|
||||||
// get it
|
// get it
|
||||||
}
|
}
|
||||||
|
@ -1904,7 +1759,7 @@ namespace ArdupilotMega
|
||||||
//dataStream.Close();
|
//dataStream.Close();
|
||||||
response.Close();
|
response.Close();
|
||||||
|
|
||||||
if (getfile)
|
if (updateThisFile)
|
||||||
{
|
{
|
||||||
if (!update)
|
if (!update)
|
||||||
{
|
{
|
||||||
|
@ -1918,16 +1773,21 @@ namespace ArdupilotMega
|
||||||
// return;
|
// return;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
if (loadinglabel != null)
|
if (frmProgressReporter != null)
|
||||||
UpdateLabel(loadinglabel, "Getting " + file);
|
frmProgressReporter.UpdateProgressAndStatus(-1, "Getting " + file);
|
||||||
|
|
||||||
// from head
|
// from head
|
||||||
long bytes = response.ContentLength;
|
long bytes = response.ContentLength;
|
||||||
|
|
||||||
// Create a request using a URL that can receive a post.
|
// Create a request using a URL that can receive a post.
|
||||||
request = WebRequest.Create(baseurl + file);
|
request = HttpWebRequest.Create(baseurl + file);
|
||||||
// Set the Method property of the request to POST.
|
// Set the Method property of the request to POST.
|
||||||
request.Method = "GET";
|
request.Method = "GET";
|
||||||
|
|
||||||
|
((HttpWebRequest)request).AutomaticDecompression = DecompressionMethods.GZip | DecompressionMethods.Deflate;
|
||||||
|
|
||||||
|
request.Headers.Add("Accept-Encoding", "gzip,deflate");
|
||||||
|
|
||||||
// Get the response.
|
// Get the response.
|
||||||
response = request.GetResponse();
|
response = request.GetResponse();
|
||||||
// Display the status.
|
// Display the status.
|
||||||
|
@ -1951,8 +1811,8 @@ namespace ArdupilotMega
|
||||||
{
|
{
|
||||||
if (dt.Second != DateTime.Now.Second)
|
if (dt.Second != DateTime.Now.Second)
|
||||||
{
|
{
|
||||||
if (loadinglabel != null)
|
if (frmProgressReporter != null)
|
||||||
UpdateLabel(loadinglabel, "Getting " + file + ": " + (((double)(contlen - bytes) / (double)contlen) * 100).ToString("0.0") + "%"); //+ Math.Abs(bytes) + " bytes");
|
frmProgressReporter.UpdateProgressAndStatus((int)(((double)(contlen - bytes) / (double)contlen) * 100), "Getting " + file + ": " + (((double)(contlen - bytes) / (double)contlen) * 100).ToString("0.0") + "%"); //+ Math.Abs(bytes) + " bytes");
|
||||||
dt = DateTime.Now;
|
dt = DateTime.Now;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -1978,11 +1838,6 @@ namespace ArdupilotMega
|
||||||
return update;
|
return update;
|
||||||
|
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
private void toolStripMenuItem3_Click(object sender, EventArgs e)
|
|
||||||
{
|
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
protected override bool ProcessCmdKey(ref Message msg, Keys keyData)
|
protected override bool ProcessCmdKey(ref Message msg, Keys keyData)
|
||||||
|
@ -1990,7 +1845,7 @@ namespace ArdupilotMega
|
||||||
if (keyData == (Keys.Control | Keys.F))
|
if (keyData == (Keys.Control | Keys.F))
|
||||||
{
|
{
|
||||||
Form frm = new temp();
|
Form frm = new temp();
|
||||||
fixtheme(frm);
|
ThemeManager.ApplyThemeTo(frm);
|
||||||
frm.Show();
|
frm.Show();
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
@ -2002,14 +1857,14 @@ namespace ArdupilotMega
|
||||||
if (keyData == (Keys.Control | Keys.G)) // test
|
if (keyData == (Keys.Control | Keys.G)) // test
|
||||||
{
|
{
|
||||||
Form frm = new SerialOutput();
|
Form frm = new SerialOutput();
|
||||||
fixtheme(frm);
|
ThemeManager.ApplyThemeTo(frm);
|
||||||
frm.Show();
|
frm.Show();
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
if (keyData == (Keys.Control | Keys.A)) // test
|
if (keyData == (Keys.Control | Keys.A)) // test
|
||||||
{
|
{
|
||||||
Form frm = new _3DRradio();
|
Form frm = new _3DRradio();
|
||||||
fixtheme(frm);
|
ThemeManager.ApplyThemeTo(frm);
|
||||||
frm.Show();
|
frm.Show();
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
@ -2019,7 +1874,7 @@ namespace ArdupilotMega
|
||||||
{
|
{
|
||||||
MainV2.comPort.Open(false);
|
MainV2.comPort.Open(false);
|
||||||
}
|
}
|
||||||
catch (Exception ex) { MessageBox.Show(ex.ToString()); }
|
catch (Exception ex) { CustomMessageBox.Show(ex.ToString()); }
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
if (keyData == (Keys.Control | Keys.Y)) // for ryan beall
|
if (keyData == (Keys.Control | Keys.Y)) // for ryan beall
|
||||||
|
@ -2032,7 +1887,7 @@ namespace ArdupilotMega
|
||||||
#else
|
#else
|
||||||
MainV2.comPort.doAction(MAVLink.MAV_ACTION.MAV_ACTION_STORAGE_WRITE);
|
MainV2.comPort.doAction(MAVLink.MAV_ACTION.MAV_ACTION_STORAGE_WRITE);
|
||||||
#endif
|
#endif
|
||||||
MessageBox.Show("Done MAV_ACTION_STORAGE_WRITE");
|
CustomMessageBox.Show("Done MAV_ACTION_STORAGE_WRITE");
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
if (keyData == (Keys.Control | Keys.J)) // for jani
|
if (keyData == (Keys.Control | Keys.J)) // for jani
|
||||||
|
|
|
@ -32,6 +32,8 @@
|
||||||
this.BUT_redokml = new ArdupilotMega.MyButton();
|
this.BUT_redokml = new ArdupilotMega.MyButton();
|
||||||
this.progressBar1 = new System.Windows.Forms.ProgressBar();
|
this.progressBar1 = new System.Windows.Forms.ProgressBar();
|
||||||
this.BUT_humanreadable = new ArdupilotMega.MyButton();
|
this.BUT_humanreadable = new ArdupilotMega.MyButton();
|
||||||
|
this.BUT_graphmavlog = new ArdupilotMega.MyButton();
|
||||||
|
this.zg1 = new ZedGraph.ZedGraphControl();
|
||||||
this.SuspendLayout();
|
this.SuspendLayout();
|
||||||
//
|
//
|
||||||
// BUT_redokml
|
// BUT_redokml
|
||||||
|
@ -53,10 +55,31 @@
|
||||||
this.BUT_humanreadable.UseVisualStyleBackColor = true;
|
this.BUT_humanreadable.UseVisualStyleBackColor = true;
|
||||||
this.BUT_humanreadable.Click += new System.EventHandler(this.BUT_humanreadable_Click);
|
this.BUT_humanreadable.Click += new System.EventHandler(this.BUT_humanreadable_Click);
|
||||||
//
|
//
|
||||||
|
// BUT_graphmavlog
|
||||||
|
//
|
||||||
|
resources.ApplyResources(this.BUT_graphmavlog, "BUT_graphmavlog");
|
||||||
|
this.BUT_graphmavlog.Name = "BUT_graphmavlog";
|
||||||
|
this.BUT_graphmavlog.UseVisualStyleBackColor = true;
|
||||||
|
this.BUT_graphmavlog.Click += new System.EventHandler(this.BUT_graphmavlog_Click);
|
||||||
|
//
|
||||||
|
// zg1
|
||||||
|
//
|
||||||
|
resources.ApplyResources(this.zg1, "zg1");
|
||||||
|
this.zg1.Name = "zg1";
|
||||||
|
this.zg1.ScrollGrace = 0D;
|
||||||
|
this.zg1.ScrollMaxX = 0D;
|
||||||
|
this.zg1.ScrollMaxY = 0D;
|
||||||
|
this.zg1.ScrollMaxY2 = 0D;
|
||||||
|
this.zg1.ScrollMinX = 0D;
|
||||||
|
this.zg1.ScrollMinY = 0D;
|
||||||
|
this.zg1.ScrollMinY2 = 0D;
|
||||||
|
//
|
||||||
// MavlinkLog
|
// MavlinkLog
|
||||||
//
|
//
|
||||||
resources.ApplyResources(this, "$this");
|
resources.ApplyResources(this, "$this");
|
||||||
this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font;
|
this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font;
|
||||||
|
this.Controls.Add(this.zg1);
|
||||||
|
this.Controls.Add(this.BUT_graphmavlog);
|
||||||
this.Controls.Add(this.BUT_humanreadable);
|
this.Controls.Add(this.BUT_humanreadable);
|
||||||
this.Controls.Add(this.progressBar1);
|
this.Controls.Add(this.progressBar1);
|
||||||
this.Controls.Add(this.BUT_redokml);
|
this.Controls.Add(this.BUT_redokml);
|
||||||
|
@ -71,5 +94,7 @@
|
||||||
private MyButton BUT_redokml;
|
private MyButton BUT_redokml;
|
||||||
private System.Windows.Forms.ProgressBar progressBar1;
|
private System.Windows.Forms.ProgressBar progressBar1;
|
||||||
private MyButton BUT_humanreadable;
|
private MyButton BUT_humanreadable;
|
||||||
|
private MyButton BUT_graphmavlog;
|
||||||
|
private ZedGraph.ZedGraphControl zg1;
|
||||||
}
|
}
|
||||||
}
|
}
|
|
@ -1,5 +1,6 @@
|
||||||
using System;
|
using System;
|
||||||
using System.Collections.Generic;
|
using System.Collections.Generic;
|
||||||
|
using System.Collections;
|
||||||
using System.ComponentModel;
|
using System.ComponentModel;
|
||||||
using System.Data;
|
using System.Data;
|
||||||
using System.Drawing;
|
using System.Drawing;
|
||||||
|
@ -22,14 +23,19 @@ using SharpKml.Dom.GX;
|
||||||
|
|
||||||
using System.Reflection;
|
using System.Reflection;
|
||||||
using System.Xml;
|
using System.Xml;
|
||||||
|
using log4net;
|
||||||
|
using ZedGraph; // Graphs
|
||||||
|
|
||||||
namespace ArdupilotMega
|
namespace ArdupilotMega
|
||||||
{
|
{
|
||||||
public partial class MavlinkLog : Form
|
public partial class MavlinkLog : Form
|
||||||
{
|
{
|
||||||
|
private static readonly ILog log = LogManager.GetLogger(System.Reflection.MethodBase.GetCurrentMethod().DeclaringType);
|
||||||
|
|
||||||
List<CurrentState> flightdata = new List<CurrentState>();
|
List<CurrentState> flightdata = new List<CurrentState>();
|
||||||
|
|
||||||
|
List<string> selection = new List<string>();
|
||||||
|
|
||||||
public MavlinkLog()
|
public MavlinkLog()
|
||||||
{
|
{
|
||||||
InitializeComponent();
|
InitializeComponent();
|
||||||
|
@ -232,7 +238,7 @@ namespace ArdupilotMega
|
||||||
}
|
}
|
||||||
catch { }
|
catch { }
|
||||||
|
|
||||||
Link link = new Link();
|
SharpKml.Dom.Link link = new SharpKml.Dom.Link();
|
||||||
link.Href = new Uri("block_plane_0.dae", UriKind.Relative);
|
link.Href = new Uri("block_plane_0.dae", UriKind.Relative);
|
||||||
|
|
||||||
model.Link = link;
|
model.Link = link;
|
||||||
|
@ -369,7 +375,7 @@ namespace ArdupilotMega
|
||||||
|
|
||||||
float oldlatlngalt = 0;
|
float oldlatlngalt = 0;
|
||||||
|
|
||||||
DateTime appui = DateTime.Now;
|
int appui = 0;
|
||||||
|
|
||||||
while (mine.logplaybackfile.BaseStream.Position < mine.logplaybackfile.BaseStream.Length)
|
while (mine.logplaybackfile.BaseStream.Position < mine.logplaybackfile.BaseStream.Length)
|
||||||
{
|
{
|
||||||
|
@ -384,11 +390,11 @@ namespace ArdupilotMega
|
||||||
|
|
||||||
cs.UpdateCurrentSettings(null, true, mine);
|
cs.UpdateCurrentSettings(null, true, mine);
|
||||||
|
|
||||||
if (appui != DateTime.Now)
|
if (appui != DateTime.Now.Second)
|
||||||
{
|
{
|
||||||
// cant do entire app as mixes with flightdata timer
|
// cant do entire app as mixes with flightdata timer
|
||||||
this.Refresh();
|
this.Refresh();
|
||||||
appui = DateTime.Now;
|
appui = DateTime.Now.Second;
|
||||||
}
|
}
|
||||||
|
|
||||||
try
|
try
|
||||||
|
@ -512,5 +518,312 @@ namespace ArdupilotMega
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
private void BUT_graphmavlog_Click(object sender, EventArgs e)
|
||||||
|
{
|
||||||
|
|
||||||
|
//http://devreminder.wordpress.com/net/net-framework-fundamentals/c-dynamic-math-expression-evaluation/
|
||||||
|
//http://www.c-sharpcorner.com/UploadFile/mgold/CodeDomCalculator08082005003253AM/CodeDomCalculator.aspx
|
||||||
|
|
||||||
|
//string mathExpression = "(1+1)*3";
|
||||||
|
//Console.WriteLine(String.Format("{0}={1}",mathExpression, Evaluate(mathExpression)));
|
||||||
|
|
||||||
|
|
||||||
|
OpenFileDialog openFileDialog1 = new OpenFileDialog();
|
||||||
|
openFileDialog1.Filter = "*.tlog|*.tlog";
|
||||||
|
openFileDialog1.FilterIndex = 2;
|
||||||
|
openFileDialog1.RestoreDirectory = true;
|
||||||
|
openFileDialog1.Multiselect = false;
|
||||||
|
try
|
||||||
|
{
|
||||||
|
openFileDialog1.InitialDirectory = Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + @"logs" + Path.DirectorySeparatorChar;
|
||||||
|
}
|
||||||
|
catch { } // incase dir doesnt exist
|
||||||
|
|
||||||
|
if (openFileDialog1.ShowDialog() == DialogResult.OK)
|
||||||
|
{
|
||||||
|
List<string> fields = GetLogFileValidFields(openFileDialog1.FileName);
|
||||||
|
|
||||||
|
zg1.GraphPane.CurveList.Clear();
|
||||||
|
|
||||||
|
GetLogFileData(zg1, openFileDialog1.FileName, fields);
|
||||||
|
|
||||||
|
try
|
||||||
|
{
|
||||||
|
// fix new line types
|
||||||
|
ThemeManager.ApplyThemeTo(this);
|
||||||
|
|
||||||
|
zg1.Invalidate();
|
||||||
|
zg1.AxisChange();
|
||||||
|
}
|
||||||
|
catch { }
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
static int[] ColourValues = new int[] {
|
||||||
|
0xFF0000,0x00FF00,0x0000FF,0xFFFF00,0xFF00FF,0x00FFFF,0x000000,
|
||||||
|
0x800000,0x008000,0x000080,0x808000,0x800080,0x008080,0x808080,
|
||||||
|
0xC00000,0x00C000,0x0000C0,0xC0C000,0xC000C0,0x00C0C0,0xC0C0C0,
|
||||||
|
0x400000,0x004000,0x000040,0x404000,0x400040,0x004040,0x404040,
|
||||||
|
0x200000,0x002000,0x000020,0x202000,0x200020,0x002020,0x202020,
|
||||||
|
0x600000,0x006000,0x000060,0x606000,0x600060,0x006060,0x606060,
|
||||||
|
0xA00000,0x00A000,0x0000A0,0xA0A000,0xA000A0,0x00A0A0,0xA0A0A0,
|
||||||
|
0xE00000,0x00E000,0x0000E0,0xE0E000,0xE000E0,0x00E0E0,0xE0E0E0,
|
||||||
|
};
|
||||||
|
|
||||||
|
|
||||||
|
private void GetLogFileData(ZedGraphControl zg1, string logfile, List<string> lookforfields)
|
||||||
|
{
|
||||||
|
if (zg1 == null)
|
||||||
|
return;
|
||||||
|
|
||||||
|
if (lookforfields != null && lookforfields.Count == 0)
|
||||||
|
return;
|
||||||
|
|
||||||
|
PointPairList[] lists = new PointPairList[lookforfields.Count];
|
||||||
|
|
||||||
|
Random rand = new Random();
|
||||||
|
|
||||||
|
int step = 0;
|
||||||
|
|
||||||
|
// setup display and arrays
|
||||||
|
for (int a = 0; a < lookforfields.Count; a++)
|
||||||
|
{
|
||||||
|
lists[a] = new PointPairList();
|
||||||
|
|
||||||
|
LineItem myCurve;
|
||||||
|
|
||||||
|
int colorvalue = ColourValues[step % ColourValues.Length];
|
||||||
|
step++;
|
||||||
|
|
||||||
|
myCurve = zg1.GraphPane.AddCurve(lookforfields[a].Replace("__mavlink_", ""), lists[a], Color.FromArgb(unchecked( colorvalue + (int)0xff000000)), SymbolType.None);
|
||||||
|
}
|
||||||
|
|
||||||
|
{
|
||||||
|
|
||||||
|
MAVLink MavlinkInterface = new MAVLink();
|
||||||
|
MavlinkInterface.logplaybackfile = new BinaryReader(File.Open(logfile, FileMode.Open, FileAccess.Read, FileShare.Read));
|
||||||
|
MavlinkInterface.logreadmode = true;
|
||||||
|
|
||||||
|
MavlinkInterface.packets.Initialize(); // clear
|
||||||
|
|
||||||
|
int appui = 0;
|
||||||
|
|
||||||
|
// to get first packet time
|
||||||
|
MavlinkInterface.readPacket();
|
||||||
|
|
||||||
|
DateTime startlogtime = MavlinkInterface.lastlogread;
|
||||||
|
|
||||||
|
while (MavlinkInterface.logplaybackfile.BaseStream.Position < MavlinkInterface.logplaybackfile.BaseStream.Length)
|
||||||
|
{
|
||||||
|
progressBar1.Value = (int)((float)MavlinkInterface.logplaybackfile.BaseStream.Position / (float)MavlinkInterface.logplaybackfile.BaseStream.Length * 100.0f);
|
||||||
|
progressBar1.Refresh();
|
||||||
|
|
||||||
|
byte[] packet = MavlinkInterface.readPacket();
|
||||||
|
|
||||||
|
object data = MavlinkInterface.DebugPacket(packet, false);
|
||||||
|
|
||||||
|
Type test = data.GetType();
|
||||||
|
|
||||||
|
foreach (var field in test.GetFields())
|
||||||
|
{
|
||||||
|
// field.Name has the field's name.
|
||||||
|
|
||||||
|
object fieldValue = field.GetValue(data); // Get value
|
||||||
|
|
||||||
|
if (field.FieldType.IsArray)
|
||||||
|
{
|
||||||
|
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
string currentitem = field.Name + " " + field.DeclaringType.Name;
|
||||||
|
int a = 0;
|
||||||
|
foreach (var lookforfield in lookforfields)
|
||||||
|
{
|
||||||
|
|
||||||
|
if (currentitem == lookforfield)
|
||||||
|
{
|
||||||
|
object value = field.GetValue(data);
|
||||||
|
// seconds scale
|
||||||
|
double time = (MavlinkInterface.lastlogread - startlogtime).TotalMilliseconds / 1000.0;
|
||||||
|
|
||||||
|
if (value.GetType() == typeof(Single))
|
||||||
|
{
|
||||||
|
lists[a].Add(time, (Single)field.GetValue(data));
|
||||||
|
}
|
||||||
|
else if (value.GetType() == typeof(short))
|
||||||
|
{
|
||||||
|
lists[a].Add(time, (short)field.GetValue(data));
|
||||||
|
}
|
||||||
|
else if (value.GetType() == typeof(ushort))
|
||||||
|
{
|
||||||
|
lists[a].Add(time, (ushort)field.GetValue(data));
|
||||||
|
}
|
||||||
|
else if (value.GetType() == typeof(byte))
|
||||||
|
{
|
||||||
|
lists[a].Add(time, (byte)field.GetValue(data));
|
||||||
|
}
|
||||||
|
else if (value.GetType() == typeof(Int32))
|
||||||
|
{
|
||||||
|
lists[a].Add(time, (Int32)field.GetValue(data));
|
||||||
|
}
|
||||||
|
}
|
||||||
|
a++;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
if (appui != DateTime.Now.Second)
|
||||||
|
{
|
||||||
|
// cant do entire app as mixes with flightdata timer
|
||||||
|
this.Refresh();
|
||||||
|
appui = DateTime.Now.Second;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
MavlinkInterface.logreadmode = false;
|
||||||
|
MavlinkInterface.logplaybackfile.Close();
|
||||||
|
MavlinkInterface.logplaybackfile = null;
|
||||||
|
|
||||||
|
|
||||||
|
//writeKML(logfile + ".kml");
|
||||||
|
|
||||||
|
progressBar1.Value = 100;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
private List<string> GetLogFileValidFields(string logfile)
|
||||||
|
{
|
||||||
|
Form selectform = SelectDataToGraphForm();
|
||||||
|
|
||||||
|
Hashtable seenIt = new Hashtable();
|
||||||
|
|
||||||
|
{
|
||||||
|
|
||||||
|
MAVLink mine = new MAVLink();
|
||||||
|
mine.logplaybackfile = new BinaryReader(File.Open(logfile, FileMode.Open, FileAccess.Read, FileShare.Read));
|
||||||
|
mine.logreadmode = true;
|
||||||
|
|
||||||
|
mine.packets.Initialize(); // clear
|
||||||
|
|
||||||
|
while (mine.logplaybackfile.BaseStream.Position < mine.logplaybackfile.BaseStream.Length)
|
||||||
|
{
|
||||||
|
progressBar1.Value = (int)((float)mine.logplaybackfile.BaseStream.Position / (float)mine.logplaybackfile.BaseStream.Length * 100.0f);
|
||||||
|
this.Refresh();
|
||||||
|
|
||||||
|
byte[] packet = mine.readPacket();
|
||||||
|
|
||||||
|
object data = mine.DebugPacket(packet, false);
|
||||||
|
|
||||||
|
Type test = data.GetType();
|
||||||
|
|
||||||
|
foreach (var field in test.GetFields())
|
||||||
|
{
|
||||||
|
// field.Name has the field's name.
|
||||||
|
|
||||||
|
object fieldValue = field.GetValue(data); // Get value
|
||||||
|
|
||||||
|
if (field.FieldType.IsArray)
|
||||||
|
{
|
||||||
|
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
if (!seenIt.ContainsKey(field.DeclaringType.Name + "." + field.Name))
|
||||||
|
{
|
||||||
|
AddDataOption(selectform, field.Name + " " + field.DeclaringType.Name);
|
||||||
|
seenIt[field.DeclaringType.Name + "." + field.Name] = 1;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
mine.logreadmode = false;
|
||||||
|
mine.logplaybackfile.Close();
|
||||||
|
mine.logplaybackfile = null;
|
||||||
|
|
||||||
|
selectform.ShowDialog();
|
||||||
|
|
||||||
|
progressBar1.Value = 100;
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
return selection;
|
||||||
|
}
|
||||||
|
|
||||||
|
private void AddDataOption(Form selectform, string Name)
|
||||||
|
{
|
||||||
|
|
||||||
|
CheckBox chk_box = new CheckBox();
|
||||||
|
|
||||||
|
log.Info("Add Option " + Name);
|
||||||
|
|
||||||
|
chk_box.Text = Name;
|
||||||
|
chk_box.Name = Name;
|
||||||
|
chk_box.Location = new System.Drawing.Point(x, y);
|
||||||
|
chk_box.Size = new System.Drawing.Size(100, 20);
|
||||||
|
chk_box.CheckedChanged += new EventHandler(chk_box_CheckedChanged);
|
||||||
|
|
||||||
|
selectform.Controls.Add(chk_box);
|
||||||
|
|
||||||
|
Application.DoEvents();
|
||||||
|
|
||||||
|
x += 0;
|
||||||
|
y += 20;
|
||||||
|
|
||||||
|
if (y > selectform.Height - 50)
|
||||||
|
{
|
||||||
|
x += 100;
|
||||||
|
y = 10;
|
||||||
|
|
||||||
|
selectform.Width = x + 100;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void chk_box_CheckedChanged(object sender, EventArgs e)
|
||||||
|
{
|
||||||
|
if (((CheckBox)sender).Checked)
|
||||||
|
{
|
||||||
|
selection.Add(((CheckBox)sender).Name);
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
selection.Remove(((CheckBox)sender).Name);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
int x = 10;
|
||||||
|
int y = 10;
|
||||||
|
|
||||||
|
private Form SelectDataToGraphForm()
|
||||||
|
{
|
||||||
|
Form selectform = new Form()
|
||||||
|
{
|
||||||
|
Name = "select",
|
||||||
|
Width = 50,
|
||||||
|
Height = 500,
|
||||||
|
Text = "Graph This"
|
||||||
|
};
|
||||||
|
|
||||||
|
x = 10;
|
||||||
|
y = 10;
|
||||||
|
|
||||||
|
{
|
||||||
|
CheckBox chk_box = new CheckBox();
|
||||||
|
chk_box.Text = "Logarithmic";
|
||||||
|
chk_box.Name = "Logarithmic";
|
||||||
|
chk_box.Location = new System.Drawing.Point(x, y);
|
||||||
|
chk_box.Size = new System.Drawing.Size(100, 20);
|
||||||
|
//chk_box.CheckedChanged += new EventHandler(chk_log_CheckedChanged);
|
||||||
|
|
||||||
|
selectform.Controls.Add(chk_box);
|
||||||
|
}
|
||||||
|
|
||||||
|
y += 20;
|
||||||
|
|
||||||
|
ThemeManager.ApplyThemeTo(selectform);
|
||||||
|
|
||||||
|
return selectform;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
|
@ -117,6 +117,10 @@
|
||||||
<resheader name="writer">
|
<resheader name="writer">
|
||||||
<value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
<value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||||
</resheader>
|
</resheader>
|
||||||
|
<assembly alias="System.Windows.Forms" name="System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089" />
|
||||||
|
<data name="BUT_redokml.Anchor" type="System.Windows.Forms.AnchorStyles, System.Windows.Forms">
|
||||||
|
<value>Top</value>
|
||||||
|
</data>
|
||||||
<assembly alias="System.Drawing" name="System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a" />
|
<assembly alias="System.Drawing" name="System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a" />
|
||||||
<data name="BUT_redokml.Location" type="System.Drawing.Point, System.Drawing">
|
<data name="BUT_redokml.Location" type="System.Drawing.Point, System.Drawing">
|
||||||
<value>45, 12</value>
|
<value>45, 12</value>
|
||||||
|
@ -135,19 +139,22 @@
|
||||||
<value>BUT_redokml</value>
|
<value>BUT_redokml</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>BUT_redokml.Type" xml:space="preserve">
|
<data name=">>BUT_redokml.Type" xml:space="preserve">
|
||||||
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
|
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>BUT_redokml.Parent" xml:space="preserve">
|
<data name=">>BUT_redokml.Parent" xml:space="preserve">
|
||||||
<value>$this</value>
|
<value>$this</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>BUT_redokml.ZOrder" xml:space="preserve">
|
<data name=">>BUT_redokml.ZOrder" xml:space="preserve">
|
||||||
<value>2</value>
|
<value>4</value>
|
||||||
|
</data>
|
||||||
|
<data name="progressBar1.Anchor" type="System.Windows.Forms.AnchorStyles, System.Windows.Forms">
|
||||||
|
<value>Top, Left, Right</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="progressBar1.Location" type="System.Drawing.Point, System.Drawing">
|
<data name="progressBar1.Location" type="System.Drawing.Point, System.Drawing">
|
||||||
<value>10, 42</value>
|
<value>10, 42</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="progressBar1.Size" type="System.Drawing.Size, System.Drawing">
|
<data name="progressBar1.Size" type="System.Drawing.Size, System.Drawing">
|
||||||
<value>313, 26</value>
|
<value>432, 26</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="progressBar1.TabIndex" type="System.Int32, mscorlib">
|
<data name="progressBar1.TabIndex" type="System.Int32, mscorlib">
|
||||||
<value>9</value>
|
<value>9</value>
|
||||||
|
@ -162,9 +169,11 @@
|
||||||
<value>$this</value>
|
<value>$this</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>progressBar1.ZOrder" xml:space="preserve">
|
<data name=">>progressBar1.ZOrder" xml:space="preserve">
|
||||||
<value>1</value>
|
<value>3</value>
|
||||||
|
</data>
|
||||||
|
<data name="BUT_humanreadable.Anchor" type="System.Windows.Forms.AnchorStyles, System.Windows.Forms">
|
||||||
|
<value>Top</value>
|
||||||
</data>
|
</data>
|
||||||
<assembly alias="System.Windows.Forms" name="System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089" />
|
|
||||||
<data name="BUT_humanreadable.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
<data name="BUT_humanreadable.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
||||||
<value>NoControl</value>
|
<value>NoControl</value>
|
||||||
</data>
|
</data>
|
||||||
|
@ -184,12 +193,66 @@
|
||||||
<value>BUT_humanreadable</value>
|
<value>BUT_humanreadable</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>BUT_humanreadable.Type" xml:space="preserve">
|
<data name=">>BUT_humanreadable.Type" xml:space="preserve">
|
||||||
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
|
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>BUT_humanreadable.Parent" xml:space="preserve">
|
<data name=">>BUT_humanreadable.Parent" xml:space="preserve">
|
||||||
<value>$this</value>
|
<value>$this</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>BUT_humanreadable.ZOrder" xml:space="preserve">
|
<data name=">>BUT_humanreadable.ZOrder" xml:space="preserve">
|
||||||
|
<value>2</value>
|
||||||
|
</data>
|
||||||
|
<data name="BUT_graphmavlog.Anchor" type="System.Windows.Forms.AnchorStyles, System.Windows.Forms">
|
||||||
|
<value>Top</value>
|
||||||
|
</data>
|
||||||
|
<data name="BUT_graphmavlog.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
||||||
|
<value>NoControl</value>
|
||||||
|
</data>
|
||||||
|
<data name="BUT_graphmavlog.Location" type="System.Drawing.Point, System.Drawing">
|
||||||
|
<value>289, 12</value>
|
||||||
|
</data>
|
||||||
|
<data name="BUT_graphmavlog.Size" type="System.Drawing.Size, System.Drawing">
|
||||||
|
<value>116, 23</value>
|
||||||
|
</data>
|
||||||
|
<data name="BUT_graphmavlog.TabIndex" type="System.Int32, mscorlib">
|
||||||
|
<value>11</value>
|
||||||
|
</data>
|
||||||
|
<data name="BUT_graphmavlog.Text" xml:space="preserve">
|
||||||
|
<value>Graph Log</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>BUT_graphmavlog.Name" xml:space="preserve">
|
||||||
|
<value>BUT_graphmavlog</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>BUT_graphmavlog.Type" xml:space="preserve">
|
||||||
|
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>BUT_graphmavlog.Parent" xml:space="preserve">
|
||||||
|
<value>$this</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>BUT_graphmavlog.ZOrder" xml:space="preserve">
|
||||||
|
<value>1</value>
|
||||||
|
</data>
|
||||||
|
<data name="zg1.Anchor" type="System.Windows.Forms.AnchorStyles, System.Windows.Forms">
|
||||||
|
<value>Top, Bottom, Left, Right</value>
|
||||||
|
</data>
|
||||||
|
<data name="zg1.Location" type="System.Drawing.Point, System.Drawing">
|
||||||
|
<value>10, 74</value>
|
||||||
|
</data>
|
||||||
|
<data name="zg1.Size" type="System.Drawing.Size, System.Drawing">
|
||||||
|
<value>434, 293</value>
|
||||||
|
</data>
|
||||||
|
<data name="zg1.TabIndex" type="System.Int32, mscorlib">
|
||||||
|
<value>12</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>zg1.Name" xml:space="preserve">
|
||||||
|
<value>zg1</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>zg1.Type" xml:space="preserve">
|
||||||
|
<value>ZedGraph.ZedGraphControl, ZedGraph, Version=5.1.2.878, Culture=neutral, PublicKeyToken=02a83cbd123fcd60</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>zg1.Parent" xml:space="preserve">
|
||||||
|
<value>$this</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>zg1.ZOrder" xml:space="preserve">
|
||||||
<value>0</value>
|
<value>0</value>
|
||||||
</data>
|
</data>
|
||||||
<metadata name="$this.Localizable" type="System.Boolean, mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089">
|
<metadata name="$this.Localizable" type="System.Boolean, mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089">
|
||||||
|
@ -199,7 +262,7 @@
|
||||||
<value>6, 13</value>
|
<value>6, 13</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="$this.ClientSize" type="System.Drawing.Size, System.Drawing">
|
<data name="$this.ClientSize" type="System.Drawing.Size, System.Drawing">
|
||||||
<value>335, 82</value>
|
<value>456, 379</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="$this.Icon" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
|
<data name="$this.Icon" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
|
||||||
<value>
|
<value>
|
||||||
|
@ -277,6 +340,9 @@
|
||||||
AAf4AAAP/AAAH/4AAD//gAD//+AD//////8=
|
AAf4AAAP/AAAH/4AAD//gAD//+AD//////8=
|
||||||
</value>
|
</value>
|
||||||
</data>
|
</data>
|
||||||
|
<data name="$this.MinimumSize" type="System.Drawing.Size, System.Drawing">
|
||||||
|
<value>472, 417</value>
|
||||||
|
</data>
|
||||||
<data name="$this.Text" xml:space="preserve">
|
<data name="$this.Text" xml:space="preserve">
|
||||||
<value>Log</value>
|
<value>Log</value>
|
||||||
</data>
|
</data>
|
||||||
|
|
|
@ -21,25 +21,28 @@ namespace ArdupilotMega
|
||||||
[STAThread]
|
[STAThread]
|
||||||
static void Main()
|
static void Main()
|
||||||
{
|
{
|
||||||
//System.Threading.Thread.CurrentThread.CurrentUICulture = new System.Globalization.CultureInfo("en-US");
|
|
||||||
//System.Threading.Thread.CurrentThread.CurrentCulture = new System.Globalization.CultureInfo("en-US");
|
|
||||||
|
|
||||||
Application.ThreadException += Application_ThreadException;
|
|
||||||
|
|
||||||
Application.Idle += Application_Idle;
|
|
||||||
|
|
||||||
//MagCalib.doWork();
|
|
||||||
|
|
||||||
//return;
|
|
||||||
|
|
||||||
//MessageBox.Show("NOTE: This version may break advanced mission scripting");
|
|
||||||
|
|
||||||
//Common.linearRegression();
|
|
||||||
|
|
||||||
Application.EnableVisualStyles();
|
Application.EnableVisualStyles();
|
||||||
XmlConfigurator.Configure();
|
XmlConfigurator.Configure();
|
||||||
log.Info("******************* Logging Configured *******************");
|
log.Info("******************* Logging Configured *******************");
|
||||||
Application.SetCompatibleTextRenderingDefault(false);
|
Application.SetCompatibleTextRenderingDefault(false);
|
||||||
|
|
||||||
|
Application.ThreadException += Application_ThreadException;
|
||||||
|
|
||||||
|
Application.Idle += Application_Idle;
|
||||||
|
|
||||||
|
//CodeGen.runCode("Sin(0.55)");
|
||||||
|
|
||||||
|
int wt = 0, ct = 0;
|
||||||
|
ThreadPool.GetMaxThreads(out wt, out ct);
|
||||||
|
log.Info("Max Threads: " + wt);
|
||||||
|
|
||||||
|
//MagCalib.ProcessLog();
|
||||||
|
|
||||||
|
//MessageBox.Show("NOTE: This version may break advanced mission scripting");
|
||||||
|
|
||||||
|
//Common.linearRegression();
|
||||||
|
|
||||||
try
|
try
|
||||||
{
|
{
|
||||||
Thread.CurrentThread.Name = "Base Thread";
|
Thread.CurrentThread.Name = "Base Thread";
|
||||||
|
@ -65,17 +68,17 @@ namespace ArdupilotMega
|
||||||
log.Debug(ex.ToString());
|
log.Debug(ex.ToString());
|
||||||
|
|
||||||
if (ex.Message == "The port is closed.") {
|
if (ex.Message == "The port is closed.") {
|
||||||
MessageBox.Show("Serial connection has been lost");
|
CustomMessageBox.Show("Serial connection has been lost");
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
if (ex.Message == "A device attached to the system is not functioning.")
|
if (ex.Message == "A device attached to the system is not functioning.")
|
||||||
{
|
{
|
||||||
MessageBox.Show("Serial connection has been lost");
|
CustomMessageBox.Show("Serial connection has been lost");
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
if (e.Exception.GetType() == typeof(MissingMethodException))
|
if (e.Exception.GetType() == typeof(MissingMethodException))
|
||||||
{
|
{
|
||||||
MessageBox.Show("Please Update - Some older library dlls are causing problems\n" + e.Exception.Message);
|
CustomMessageBox.Show("Please Update - Some older library dlls are causing problems\n" + e.Exception.Message);
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
if (e.Exception.GetType() == typeof(ObjectDisposedException) || e.Exception.GetType() == typeof(InvalidOperationException)) // something is trying to update while the form, is closing.
|
if (e.Exception.GetType() == typeof(ObjectDisposedException) || e.Exception.GetType() == typeof(InvalidOperationException)) // something is trying to update while the form, is closing.
|
||||||
|
@ -84,10 +87,10 @@ namespace ArdupilotMega
|
||||||
}
|
}
|
||||||
if (e.Exception.GetType() == typeof(FileNotFoundException) || e.Exception.GetType() == typeof(BadImageFormatException)) // i get alot of error from people who click the exe from inside a zip file.
|
if (e.Exception.GetType() == typeof(FileNotFoundException) || e.Exception.GetType() == typeof(BadImageFormatException)) // i get alot of error from people who click the exe from inside a zip file.
|
||||||
{
|
{
|
||||||
MessageBox.Show("You are missing some DLL's. Please extract the zip file somewhere. OR Use the update feature from the menu");
|
CustomMessageBox.Show("You are missing some DLL's. Please extract the zip file somewhere. OR Use the update feature from the menu");
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
DialogResult dr = MessageBox.Show("An error has occurred\n"+ex.ToString() + "\n\nReport this Error???", "Send Error", MessageBoxButtons.YesNo);
|
DialogResult dr = CustomMessageBox.Show("An error has occurred\n"+ex.ToString() + "\n\nReport this Error???", "Send Error", MessageBoxButtons.YesNo);
|
||||||
if (DialogResult.Yes == dr)
|
if (DialogResult.Yes == dr)
|
||||||
{
|
{
|
||||||
try
|
try
|
||||||
|
@ -129,7 +132,7 @@ namespace ArdupilotMega
|
||||||
}
|
}
|
||||||
catch
|
catch
|
||||||
{
|
{
|
||||||
MessageBox.Show("Error sending Error report!! Youre most likerly are not on the internet");
|
CustomMessageBox.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:
|
// by using the '*' as shown below:
|
||||||
// [assembly: AssemblyVersion("1.0.*")]
|
// [assembly: AssemblyVersion("1.0.*")]
|
||||||
[assembly: AssemblyVersion("1.0.0.0")]
|
[assembly: AssemblyVersion("1.0.0.0")]
|
||||||
[assembly: AssemblyFileVersion("1.1.46")]
|
[assembly: AssemblyFileVersion("1.1.51")]
|
||||||
[assembly: NeutralResourcesLanguageAttribute("")]
|
[assembly: NeutralResourcesLanguageAttribute("")]
|
||||||
|
|
|
@ -1,7 +1,7 @@
|
||||||
//------------------------------------------------------------------------------
|
//------------------------------------------------------------------------------
|
||||||
// <auto-generated>
|
// <auto-generated>
|
||||||
// This code was generated by a tool.
|
// This code was generated by a tool.
|
||||||
// Runtime Version:4.0.30319.239
|
// Runtime Version:4.0.30319.261
|
||||||
//
|
//
|
||||||
// Changes to this file may cause incorrect behavior and will be lost if
|
// Changes to this file may cause incorrect behavior and will be lost if
|
||||||
// the code is regenerated.
|
// the code is regenerated.
|
||||||
|
|
|
@ -190,47 +190,6 @@ namespace ArdupilotMega
|
||||||
else { list6.Clear(); }
|
else { list6.Clear(); }
|
||||||
}
|
}
|
||||||
|
|
||||||
public static string CustomMessageBox(string title, string promptText, string buttontext1, string buttontext2)
|
|
||||||
{
|
|
||||||
Form form = new Form();
|
|
||||||
System.Windows.Forms.Label label = new System.Windows.Forms.Label();
|
|
||||||
Button button1 = new Button();
|
|
||||||
Button button2 = new Button();
|
|
||||||
|
|
||||||
form.Text = title;
|
|
||||||
label.Text = promptText;
|
|
||||||
|
|
||||||
button1.Text = buttontext1;
|
|
||||||
button2.Text = buttontext2;
|
|
||||||
button1.DialogResult = DialogResult.OK;
|
|
||||||
button2.DialogResult = DialogResult.Cancel;
|
|
||||||
|
|
||||||
label.SetBounds(9, 10, 372, 13);
|
|
||||||
button1.SetBounds(228, 72, 75, 23);
|
|
||||||
button2.SetBounds(309, 72, 75, 23);
|
|
||||||
|
|
||||||
label.AutoSize = true;
|
|
||||||
button1.Anchor = AnchorStyles.Bottom | AnchorStyles.Right;
|
|
||||||
button2.Anchor = AnchorStyles.Bottom | AnchorStyles.Right;
|
|
||||||
|
|
||||||
form.ClientSize = new Size(396, 107);
|
|
||||||
form.Controls.AddRange(new Control[] { label, button1, button2 });
|
|
||||||
form.ClientSize = new Size(Math.Max(300, label.Right + 10), form.ClientSize.Height);
|
|
||||||
form.FormBorderStyle = FormBorderStyle.FixedDialog;
|
|
||||||
form.StartPosition = FormStartPosition.CenterScreen;
|
|
||||||
form.MinimizeBox = false;
|
|
||||||
form.MaximizeBox = false;
|
|
||||||
form.AcceptButton = button1;
|
|
||||||
form.CancelButton = button2;
|
|
||||||
|
|
||||||
DialogResult dialogResult = form.ShowDialog();
|
|
||||||
if (dialogResult == DialogResult.OK)
|
|
||||||
{
|
|
||||||
return buttontext1;
|
|
||||||
}
|
|
||||||
return buttontext2;
|
|
||||||
}
|
|
||||||
|
|
||||||
private void ACM_Setup_Load(object sender, EventArgs e)
|
private void ACM_Setup_Load(object sender, EventArgs e)
|
||||||
{
|
{
|
||||||
|
|
||||||
|
@ -274,7 +233,7 @@ namespace ArdupilotMega
|
||||||
|
|
||||||
if (!comPort.BaseStream.IsOpen && !MainV2.comPort.logreadmode)
|
if (!comPort.BaseStream.IsOpen && !MainV2.comPort.logreadmode)
|
||||||
{
|
{
|
||||||
MessageBox.Show("Please connect first");
|
CustomMessageBox.Show("Please connect first");
|
||||||
this.Close();
|
this.Close();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -292,7 +251,7 @@ namespace ArdupilotMega
|
||||||
}
|
}
|
||||||
catch
|
catch
|
||||||
{
|
{
|
||||||
MessageBox.Show("Comport open failed");
|
CustomMessageBox.Show("Comport open failed");
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
timer1.Start();
|
timer1.Start();
|
||||||
|
|
|
@ -29,6 +29,7 @@
|
||||||
private void InitializeComponent()
|
private void InitializeComponent()
|
||||||
{
|
{
|
||||||
this.components = new System.ComponentModel.Container();
|
this.components = new System.ComponentModel.Container();
|
||||||
|
System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(_3DRradio));
|
||||||
this.Progressbar = new System.Windows.Forms.ProgressBar();
|
this.Progressbar = new System.Windows.Forms.ProgressBar();
|
||||||
this.S1 = new System.Windows.Forms.ComboBox();
|
this.S1 = new System.Windows.Forms.ComboBox();
|
||||||
this.label1 = new System.Windows.Forms.Label();
|
this.label1 = new System.Windows.Forms.Label();
|
||||||
|
@ -97,7 +98,7 @@
|
||||||
this.S1.Name = "S1";
|
this.S1.Name = "S1";
|
||||||
this.S1.Size = new System.Drawing.Size(80, 21);
|
this.S1.Size = new System.Drawing.Size(80, 21);
|
||||||
this.S1.TabIndex = 4;
|
this.S1.TabIndex = 4;
|
||||||
this.toolTip1.SetToolTip(this.S1, "Serial Baud Rate 57 = 57600");
|
this.toolTip1.SetToolTip(this.S1, "Serial baud rate in rounded kbps. So 57 means 57600. \r\n");
|
||||||
//
|
//
|
||||||
// label1
|
// label1
|
||||||
//
|
//
|
||||||
|
@ -149,7 +150,9 @@
|
||||||
this.S2.Name = "S2";
|
this.S2.Name = "S2";
|
||||||
this.S2.Size = new System.Drawing.Size(80, 21);
|
this.S2.Size = new System.Drawing.Size(80, 21);
|
||||||
this.S2.TabIndex = 9;
|
this.S2.TabIndex = 9;
|
||||||
this.toolTip1.SetToolTip(this.S2, "the inter-radio data rate in rounded kbps. So 128 means");
|
this.toolTip1.SetToolTip(this.S2, "AIR_SPEED is the inter-radio data rate in rounded kbps. So 128 means 128kbps. Max" +
|
||||||
|
" is 192, min is 2. I would not recommend values below 16 as the frequency hoppin" +
|
||||||
|
"g and tdm sync times get too long. ");
|
||||||
//
|
//
|
||||||
// label4
|
// label4
|
||||||
//
|
//
|
||||||
|
@ -198,7 +201,7 @@
|
||||||
this.S3.Name = "S3";
|
this.S3.Name = "S3";
|
||||||
this.S3.Size = new System.Drawing.Size(80, 21);
|
this.S3.Size = new System.Drawing.Size(80, 21);
|
||||||
this.S3.TabIndex = 11;
|
this.S3.TabIndex = 11;
|
||||||
this.toolTip1.SetToolTip(this.S3, "a 16 bit \'network ID\'. This is used to seed the frequency");
|
this.toolTip1.SetToolTip(this.S3, resources.GetString("S3.ToolTip"));
|
||||||
//
|
//
|
||||||
// label5
|
// label5
|
||||||
//
|
//
|
||||||
|
@ -238,7 +241,8 @@
|
||||||
this.S4.Name = "S4";
|
this.S4.Name = "S4";
|
||||||
this.S4.Size = new System.Drawing.Size(80, 21);
|
this.S4.Size = new System.Drawing.Size(80, 21);
|
||||||
this.S4.TabIndex = 13;
|
this.S4.TabIndex = 13;
|
||||||
this.toolTip1.SetToolTip(this.S4, "the transmit power in dBm. 20dBm is 100mW. It is useful to");
|
this.toolTip1.SetToolTip(this.S4, "TXPOWER is the transmit power in dBm. 20dBm is 100mW. It is useful to set this to" +
|
||||||
|
" lower levels for short range testing.\r\n");
|
||||||
//
|
//
|
||||||
// label6
|
// label6
|
||||||
//
|
//
|
||||||
|
@ -255,7 +259,7 @@
|
||||||
this.S5.Name = "S5";
|
this.S5.Name = "S5";
|
||||||
this.S5.Size = new System.Drawing.Size(80, 21);
|
this.S5.Size = new System.Drawing.Size(80, 21);
|
||||||
this.S5.TabIndex = 15;
|
this.S5.TabIndex = 15;
|
||||||
this.toolTip1.SetToolTip(this.S5, "to enable/disable the golay error correcting code. It defaults");
|
this.toolTip1.SetToolTip(this.S5, resources.GetString("S5.ToolTip"));
|
||||||
//
|
//
|
||||||
// label7
|
// label7
|
||||||
//
|
//
|
||||||
|
@ -272,7 +276,7 @@
|
||||||
this.S6.Name = "S6";
|
this.S6.Name = "S6";
|
||||||
this.S6.Size = new System.Drawing.Size(80, 21);
|
this.S6.Size = new System.Drawing.Size(80, 21);
|
||||||
this.S6.TabIndex = 17;
|
this.S6.TabIndex = 17;
|
||||||
this.toolTip1.SetToolTip(this.S6, "enables/disables MAVLink packet framing. This tries to align");
|
this.toolTip1.SetToolTip(this.S6, resources.GetString("S6.ToolTip"));
|
||||||
//
|
//
|
||||||
// label8
|
// label8
|
||||||
//
|
//
|
||||||
|
@ -289,7 +293,7 @@
|
||||||
this.S7.Name = "S7";
|
this.S7.Name = "S7";
|
||||||
this.S7.Size = new System.Drawing.Size(80, 21);
|
this.S7.Size = new System.Drawing.Size(80, 21);
|
||||||
this.S7.TabIndex = 19;
|
this.S7.TabIndex = 19;
|
||||||
this.toolTip1.SetToolTip(this.S7, "enables/disables \"opportunistic resend\". When enabled the");
|
this.toolTip1.SetToolTip(this.S7, resources.GetString("S7.ToolTip"));
|
||||||
//
|
//
|
||||||
// RS7
|
// RS7
|
||||||
//
|
//
|
||||||
|
@ -297,7 +301,7 @@
|
||||||
this.RS7.Name = "RS7";
|
this.RS7.Name = "RS7";
|
||||||
this.RS7.Size = new System.Drawing.Size(80, 21);
|
this.RS7.Size = new System.Drawing.Size(80, 21);
|
||||||
this.RS7.TabIndex = 29;
|
this.RS7.TabIndex = 29;
|
||||||
this.toolTip1.SetToolTip(this.RS7, "enables/disables \"opportunistic resend\". When enabled the");
|
this.toolTip1.SetToolTip(this.RS7, resources.GetString("RS7.ToolTip"));
|
||||||
//
|
//
|
||||||
// RS6
|
// RS6
|
||||||
//
|
//
|
||||||
|
@ -305,7 +309,7 @@
|
||||||
this.RS6.Name = "RS6";
|
this.RS6.Name = "RS6";
|
||||||
this.RS6.Size = new System.Drawing.Size(80, 21);
|
this.RS6.Size = new System.Drawing.Size(80, 21);
|
||||||
this.RS6.TabIndex = 28;
|
this.RS6.TabIndex = 28;
|
||||||
this.toolTip1.SetToolTip(this.RS6, "enables/disables MAVLink packet framing. This tries to align");
|
this.toolTip1.SetToolTip(this.RS6, resources.GetString("RS6.ToolTip"));
|
||||||
//
|
//
|
||||||
// RS5
|
// RS5
|
||||||
//
|
//
|
||||||
|
@ -313,7 +317,7 @@
|
||||||
this.RS5.Name = "RS5";
|
this.RS5.Name = "RS5";
|
||||||
this.RS5.Size = new System.Drawing.Size(80, 21);
|
this.RS5.Size = new System.Drawing.Size(80, 21);
|
||||||
this.RS5.TabIndex = 27;
|
this.RS5.TabIndex = 27;
|
||||||
this.toolTip1.SetToolTip(this.RS5, "to enable/disable the golay error correcting code. It defaults");
|
this.toolTip1.SetToolTip(this.RS5, resources.GetString("RS5.ToolTip"));
|
||||||
//
|
//
|
||||||
// RS4
|
// RS4
|
||||||
//
|
//
|
||||||
|
@ -344,7 +348,8 @@
|
||||||
this.RS4.Name = "RS4";
|
this.RS4.Name = "RS4";
|
||||||
this.RS4.Size = new System.Drawing.Size(80, 21);
|
this.RS4.Size = new System.Drawing.Size(80, 21);
|
||||||
this.RS4.TabIndex = 26;
|
this.RS4.TabIndex = 26;
|
||||||
this.toolTip1.SetToolTip(this.RS4, "the transmit power in dBm. 20dBm is 100mW. It is useful to");
|
this.toolTip1.SetToolTip(this.RS4, "TXPOWER is the transmit power in dBm. 20dBm is 100mW. It is useful to set this to" +
|
||||||
|
" lower levels for short range testing.\r\n");
|
||||||
//
|
//
|
||||||
// RS3
|
// RS3
|
||||||
//
|
//
|
||||||
|
@ -384,7 +389,7 @@
|
||||||
this.RS3.Name = "RS3";
|
this.RS3.Name = "RS3";
|
||||||
this.RS3.Size = new System.Drawing.Size(80, 21);
|
this.RS3.Size = new System.Drawing.Size(80, 21);
|
||||||
this.RS3.TabIndex = 25;
|
this.RS3.TabIndex = 25;
|
||||||
this.toolTip1.SetToolTip(this.RS3, "a 16 bit \'network ID\'. This is used to seed the frequency");
|
this.toolTip1.SetToolTip(this.RS3, resources.GetString("RS3.ToolTip"));
|
||||||
//
|
//
|
||||||
// RS2
|
// RS2
|
||||||
//
|
//
|
||||||
|
@ -401,7 +406,9 @@
|
||||||
this.RS2.Name = "RS2";
|
this.RS2.Name = "RS2";
|
||||||
this.RS2.Size = new System.Drawing.Size(80, 21);
|
this.RS2.Size = new System.Drawing.Size(80, 21);
|
||||||
this.RS2.TabIndex = 24;
|
this.RS2.TabIndex = 24;
|
||||||
this.toolTip1.SetToolTip(this.RS2, "the inter-radio data rate in rounded kbps. So 128 means");
|
this.toolTip1.SetToolTip(this.RS2, "AIR_SPEED is the inter-radio data rate in rounded kbps. So 128 means 128kbps. Max" +
|
||||||
|
" is 192, min is 2. I would not recommend values below 16 as the frequency hoppin" +
|
||||||
|
"g and tdm sync times get too long. ");
|
||||||
//
|
//
|
||||||
// RS1
|
// RS1
|
||||||
//
|
//
|
||||||
|
@ -420,7 +427,7 @@
|
||||||
this.RS1.Name = "RS1";
|
this.RS1.Name = "RS1";
|
||||||
this.RS1.Size = new System.Drawing.Size(80, 21);
|
this.RS1.Size = new System.Drawing.Size(80, 21);
|
||||||
this.RS1.TabIndex = 22;
|
this.RS1.TabIndex = 22;
|
||||||
this.toolTip1.SetToolTip(this.RS1, "Serial Baud Rate 57 = 57600");
|
this.toolTip1.SetToolTip(this.RS1, "Serial baud rate in rounded kbps. So 57 means 57600. \r\n");
|
||||||
//
|
//
|
||||||
// RS0
|
// RS0
|
||||||
//
|
//
|
||||||
|
@ -472,6 +479,7 @@
|
||||||
this.RSSI.ReadOnly = true;
|
this.RSSI.ReadOnly = true;
|
||||||
this.RSSI.Size = new System.Drawing.Size(194, 58);
|
this.RSSI.Size = new System.Drawing.Size(194, 58);
|
||||||
this.RSSI.TabIndex = 34;
|
this.RSSI.TabIndex = 34;
|
||||||
|
this.toolTip1.SetToolTip(this.RSSI, resources.GetString("RSSI.ToolTip"));
|
||||||
//
|
//
|
||||||
// label11
|
// label11
|
||||||
//
|
//
|
||||||
|
@ -605,6 +613,7 @@
|
||||||
this.Controls.Add(this.lbl_status);
|
this.Controls.Add(this.lbl_status);
|
||||||
this.Controls.Add(this.Progressbar);
|
this.Controls.Add(this.Progressbar);
|
||||||
this.Controls.Add(this.BUT_upload);
|
this.Controls.Add(this.BUT_upload);
|
||||||
|
this.Icon = ((System.Drawing.Icon)(resources.GetObject("$this.Icon")));
|
||||||
this.MaximizeBox = false;
|
this.MaximizeBox = false;
|
||||||
this.MinimizeBox = false;
|
this.MinimizeBox = false;
|
||||||
this.MinimumSize = new System.Drawing.Size(334, 482);
|
this.MinimumSize = new System.Drawing.Size(334, 482);
|
||||||
|
|
|
@ -59,7 +59,7 @@ namespace ArdupilotMega
|
||||||
comPort.Open();
|
comPort.Open();
|
||||||
|
|
||||||
}
|
}
|
||||||
catch { MessageBox.Show("Invalid ComPort or in use"); return; }
|
catch { CustomMessageBox.Show("Invalid ComPort or in use"); return; }
|
||||||
|
|
||||||
bool bootloadermode = false;
|
bool bootloadermode = false;
|
||||||
|
|
||||||
|
@ -99,7 +99,7 @@ namespace ArdupilotMega
|
||||||
{
|
{
|
||||||
iHex.load(firmwarefile);
|
iHex.load(firmwarefile);
|
||||||
}
|
}
|
||||||
catch { MessageBox.Show("Bad Firmware File"); goto exit; }
|
catch { CustomMessageBox.Show("Bad Firmware File"); goto exit; }
|
||||||
|
|
||||||
if (!bootloadermode)
|
if (!bootloadermode)
|
||||||
{
|
{
|
||||||
|
@ -118,16 +118,16 @@ namespace ArdupilotMega
|
||||||
{
|
{
|
||||||
uploader.upload(comPort, iHex);
|
uploader.upload(comPort, iHex);
|
||||||
}
|
}
|
||||||
catch (Exception ex) { MessageBox.Show("Upload Failed " + ex.Message); }
|
catch (Exception ex) { CustomMessageBox.Show("Upload Failed " + ex.Message); }
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
MessageBox.Show("Failed to download new firmware");
|
CustomMessageBox.Show("Failed to download new firmware");
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
MessageBox.Show("Failed to identify Radio");
|
CustomMessageBox.Show("Failed to identify Radio");
|
||||||
}
|
}
|
||||||
|
|
||||||
exit:
|
exit:
|
||||||
|
@ -198,7 +198,7 @@ namespace ArdupilotMega
|
||||||
|
|
||||||
|
|
||||||
}
|
}
|
||||||
catch { MessageBox.Show("Invalid ComPort or in use"); return; }
|
catch { CustomMessageBox.Show("Invalid ComPort or in use"); return; }
|
||||||
|
|
||||||
lbl_status.Text = "Connecting";
|
lbl_status.Text = "Connecting";
|
||||||
|
|
||||||
|
@ -242,7 +242,7 @@ namespace ArdupilotMega
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
MessageBox.Show("Set Command error");
|
CustomMessageBox.Show("Set Command error");
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -258,7 +258,7 @@ namespace ArdupilotMega
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
MessageBox.Show("Set Command error");
|
CustomMessageBox.Show("Set Command error");
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -309,7 +309,7 @@ namespace ArdupilotMega
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
MessageBox.Show("Set Command error");
|
CustomMessageBox.Show("Set Command error");
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -325,7 +325,7 @@ namespace ArdupilotMega
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
MessageBox.Show("Set Command error");
|
CustomMessageBox.Show("Set Command error");
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -351,7 +351,7 @@ namespace ArdupilotMega
|
||||||
doCommand(comPort, "ATZ");
|
doCommand(comPort, "ATZ");
|
||||||
|
|
||||||
lbl_status.Text = "Fail";
|
lbl_status.Text = "Fail";
|
||||||
MessageBox.Show("Failed to enter command mode");
|
CustomMessageBox.Show("Failed to enter command mode");
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
@ -374,7 +374,7 @@ namespace ArdupilotMega
|
||||||
|
|
||||||
|
|
||||||
}
|
}
|
||||||
catch { MessageBox.Show("Invalid ComPort or in use"); return; }
|
catch { CustomMessageBox.Show("Invalid ComPort or in use"); return; }
|
||||||
|
|
||||||
lbl_status.Text = "Connecting";
|
lbl_status.Text = "Connecting";
|
||||||
|
|
||||||
|
@ -479,7 +479,7 @@ namespace ArdupilotMega
|
||||||
doCommand(comPort, "ATO");
|
doCommand(comPort, "ATO");
|
||||||
|
|
||||||
lbl_status.Text = "Fail";
|
lbl_status.Text = "Fail";
|
||||||
MessageBox.Show("Failed to enter command mode");
|
CustomMessageBox.Show("Failed to enter command mode");
|
||||||
}
|
}
|
||||||
|
|
||||||
comPort.Close();
|
comPort.Close();
|
||||||
|
|
|
@ -120,4 +120,124 @@
|
||||||
<metadata name="toolTip1.TrayLocation" type="System.Drawing.Point, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a">
|
<metadata name="toolTip1.TrayLocation" type="System.Drawing.Point, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a">
|
||||||
<value>17, 17</value>
|
<value>17, 17</value>
|
||||||
</metadata>
|
</metadata>
|
||||||
|
<metadata name="toolTip1.TrayLocation" type="System.Drawing.Point, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a">
|
||||||
|
<value>17, 17</value>
|
||||||
|
</metadata>
|
||||||
|
<data name="S3.ToolTip" xml:space="preserve">
|
||||||
|
<value>NETID is a 16 bit 'network ID'. This is used to seed the frequency hopping sequence and to identify packets as coming from the right radio. Make sure you use a different NETID from anyone else running the same sort of radio in the area. </value>
|
||||||
|
</data>
|
||||||
|
<data name="S5.ToolTip" xml:space="preserve">
|
||||||
|
<value>ECC is to enable/disable the golay error correcting code. It defaults to off. If you enable it then you packets take twice as many bytes to send, so you lose half your air bandwidth, but it can correct up to 3 bit errors per 12 bits of data. Use this for long range, usually in combination with a lower air data rate. The golay decode takes 20 microsecond per transmitted byte (40 microseconds per user data byte) which means you will also be a bit CPU constrained at the highest air data rates. So you usually use golay at 128kbps or less.
|
||||||
|
</value>
|
||||||
|
</data>
|
||||||
|
<data name="S6.ToolTip" xml:space="preserve">
|
||||||
|
<value>MAVLINK enables/disables MAVLink packet framing. This tries to align radio packets to MAVLink packet boundaries, which makes a big difference to what happens to the MAVLink stream when you lose a packet.
|
||||||
|
</value>
|
||||||
|
</data>
|
||||||
|
<data name="S7.ToolTip" xml:space="preserve">
|
||||||
|
<value>OPPRESEND enables/disables "opportunistic resend". When enabled the radio will send a packet twice if the serial input buffer has less than 256 bytes in it. The 2nd send is marked as a resend and discarded by the receiving radio if it got the first packet OK. This makes a big difference to the link quality, especially for uplink commands.
|
||||||
|
</value>
|
||||||
|
</data>
|
||||||
|
<data name="RS7.ToolTip" xml:space="preserve">
|
||||||
|
<value>OPPRESEND enables/disables "opportunistic resend". When enabled the radio will send a packet twice if the serial input buffer has less than 256 bytes in it. The 2nd send is marked as a resend and discarded by the receiving radio if it got the first packet OK. This makes a big difference to the link quality, especially for uplink commands.
|
||||||
|
</value>
|
||||||
|
</data>
|
||||||
|
<data name="RS6.ToolTip" xml:space="preserve">
|
||||||
|
<value>MAVLINK enables/disables MAVLink packet framing. This tries to align radio packets to MAVLink packet boundaries, which makes a big difference to what happens to the MAVLink stream when you lose a packet.
|
||||||
|
</value>
|
||||||
|
</data>
|
||||||
|
<data name="RS5.ToolTip" xml:space="preserve">
|
||||||
|
<value>ECC is to enable/disable the golay error correcting code. It defaults to off. If you enable it then you packets take twice as many bytes to send, so you lose half your air bandwidth, but it can correct up to 3 bit errors per 12 bits of data. Use this for long range, usually in combination with a lower air data rate. The golay decode takes 20 microsecond per transmitted byte (40 microseconds per user data byte) which means you will also be a bit CPU constrained at the highest air data rates. So you usually use golay at 128kbps or less.
|
||||||
|
</value>
|
||||||
|
</data>
|
||||||
|
<data name="RS3.ToolTip" xml:space="preserve">
|
||||||
|
<value>NETID is a 16 bit 'network ID'. This is used to seed the frequency hopping sequence and to identify packets as coming from the right radio. Make sure you use a different NETID from anyone else running the same sort of radio in the area. </value>
|
||||||
|
</data>
|
||||||
|
<data name="RSSI.ToolTip" xml:space="preserve">
|
||||||
|
<value>see the spec for a RSSI to dBm graph. The numbers at the end are:
|
||||||
|
txe: number of transmit errors (eg. transmit timeouts)
|
||||||
|
rxe: number of receive errors (crc error, framing error etc)
|
||||||
|
stx: number of serial transmit overflows
|
||||||
|
rrx: number of serial receive overflows
|
||||||
|
ecc: number of 12 bit words successfully corrected by the golay code
|
||||||
|
which result in a valid packet CRC
|
||||||
|
</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>
|
||||||
</root>
|
</root>
|
|
@ -184,21 +184,21 @@ namespace resedit
|
||||||
{
|
{
|
||||||
sw.Write("<tr><td>" + row.Cells[colFile.Index].Value.ToString() + "</td><td>" + row.Cells[colInternal.Index].Value.ToString() + "</td><td>" + row.Cells[colOtherLang.Index].Value.ToString() + "</td></tr>");
|
sw.Write("<tr><td>" + row.Cells[colFile.Index].Value.ToString() + "</td><td>" + row.Cells[colInternal.Index].Value.ToString() + "</td><td>" + row.Cells[colOtherLang.Index].Value.ToString() + "</td></tr>");
|
||||||
}
|
}
|
||||||
catch (Exception ex) { try { MessageBox.Show("Failed to save " + row.Cells[colOtherLang.Index].Value.ToString() + " " + ex.ToString()); } catch { } }
|
catch (Exception ex) { try { CustomMessageBox.Show("Failed to save " + row.Cells[colOtherLang.Index].Value.ToString() + " " + ex.ToString()); } catch { } }
|
||||||
}
|
}
|
||||||
if (writer != null)
|
if (writer != null)
|
||||||
writer.Close();
|
writer.Close();
|
||||||
sw.Write("</table></html>");
|
sw.Write("</table></html>");
|
||||||
sw.Close();
|
sw.Close();
|
||||||
|
|
||||||
MessageBox.Show("Saved");
|
CustomMessageBox.Show("Saved");
|
||||||
}
|
}
|
||||||
|
|
||||||
private void button3_Click(object sender, EventArgs e)
|
private void button3_Click(object sender, EventArgs e)
|
||||||
{
|
{
|
||||||
if (!File.Exists("translation/output.html"))
|
if (!File.Exists("translation/output.html"))
|
||||||
{
|
{
|
||||||
MessageBox.Show("No existing translation has been done");
|
CustomMessageBox.Show("No existing translation has been done");
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -230,7 +230,7 @@ namespace resedit
|
||||||
|
|
||||||
sr1.Close();
|
sr1.Close();
|
||||||
|
|
||||||
MessageBox.Show("Modified "+a+" entries");
|
CustomMessageBox.Show("Modified "+a+" entries");
|
||||||
}
|
}
|
||||||
|
|
||||||
private void comboBox1_SelectedIndexChanged(object sender, EventArgs e)
|
private void comboBox1_SelectedIndexChanged(object sender, EventArgs e)
|
||||||
|
@ -292,7 +292,7 @@ namespace resedit
|
||||||
catch { }
|
catch { }
|
||||||
}
|
}
|
||||||
|
|
||||||
MessageBox.Show("Loaded Existing");
|
CustomMessageBox.Show("Loaded Existing");
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
|
@ -24,11 +24,12 @@ namespace ArdupilotMega
|
||||||
if (engine != null)
|
if (engine != null)
|
||||||
engine.Runtime.Shutdown();
|
engine.Runtime.Shutdown();
|
||||||
|
|
||||||
engine = Python.CreateEngine(options);
|
engine = Python.CreateEngine(options);
|
||||||
scope = engine.CreateScope();
|
scope = engine.CreateScope();
|
||||||
|
|
||||||
scope.SetVariable("cs", MainV2.cs);
|
scope.SetVariable("cs", MainV2.cs);
|
||||||
scope.SetVariable("Script", this);
|
scope.SetVariable("Script", this);
|
||||||
|
scope.SetVariable("mavutil", this);
|
||||||
|
|
||||||
engine.CreateScriptSourceFromString("print 'hello world from python'").Execute(scope);
|
engine.CreateScriptSourceFromString("print 'hello world from python'").Execute(scope);
|
||||||
engine.CreateScriptSourceFromString("print cs.roll").Execute(scope);
|
engine.CreateScriptSourceFromString("print cs.roll").Execute(scope);
|
||||||
|
@ -54,8 +55,22 @@ namespace ArdupilotMega
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
public object mavlink_connection(string device, int baud = 115200, int source_system = 255,
|
||||||
|
bool write = false, bool append = false,
|
||||||
|
bool robust_parsing = true, bool notimestamps = false, bool input = true)
|
||||||
|
{
|
||||||
|
|
||||||
public void Sleep(int ms) {
|
return null;
|
||||||
|
}
|
||||||
|
|
||||||
|
public object recv_match(string condition = null, string type = null, bool blocking = false)
|
||||||
|
{
|
||||||
|
|
||||||
|
return null;
|
||||||
|
}
|
||||||
|
|
||||||
|
public void Sleep(int ms)
|
||||||
|
{
|
||||||
System.Threading.Thread.Sleep(ms);
|
System.Threading.Thread.Sleep(ms);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -67,7 +82,7 @@ namespace ArdupilotMega
|
||||||
}
|
}
|
||||||
catch (Exception e)
|
catch (Exception e)
|
||||||
{
|
{
|
||||||
System.Windows.Forms.MessageBox.Show("Error running script " + e.Message);
|
System.Windows.Forms.CustomMessageBox.Show("Error running script " + e.Message);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -104,7 +119,8 @@ namespace ArdupilotMega
|
||||||
public bool WaitFor(string message, int timeout)
|
public bool WaitFor(string message, int timeout)
|
||||||
{
|
{
|
||||||
int timein = 0;
|
int timein = 0;
|
||||||
while (!MainV2.cs.message.Contains(message)) {
|
while (!MainV2.cs.message.Contains(message))
|
||||||
|
{
|
||||||
System.Threading.Thread.Sleep(5);
|
System.Threading.Thread.Sleep(5);
|
||||||
timein += 5;
|
timein += 5;
|
||||||
if (timein > timeout)
|
if (timein > timeout)
|
||||||
|
@ -113,8 +129,8 @@ namespace ArdupilotMega
|
||||||
|
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
public bool SendRC(int channel, ushort pwm,bool sendnow)
|
public bool SendRC(int channel, ushort pwm, bool sendnow)
|
||||||
{
|
{
|
||||||
switch (channel)
|
switch (channel)
|
||||||
{
|
{
|
||||||
|
@ -166,4 +182,4 @@ namespace ArdupilotMega
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
|
@ -45,13 +45,13 @@ namespace ArdupilotMega
|
||||||
{
|
{
|
||||||
comPort.PortName = CMB_serialport.Text;
|
comPort.PortName = CMB_serialport.Text;
|
||||||
}
|
}
|
||||||
catch { MessageBox.Show("Invalid PortName"); return; }
|
catch { CustomMessageBox.Show("Invalid PortName"); return; }
|
||||||
try {
|
try {
|
||||||
comPort.BaudRate = int.Parse(CMB_baudrate.Text);
|
comPort.BaudRate = int.Parse(CMB_baudrate.Text);
|
||||||
} catch {MessageBox.Show("Invalid BaudRate"); return;}
|
} catch {CustomMessageBox.Show("Invalid BaudRate"); return;}
|
||||||
try {
|
try {
|
||||||
comPort.Open();
|
comPort.Open();
|
||||||
} catch {MessageBox.Show("Error Connecting\nif using com0com please rename the ports to COM??"); return;}
|
} catch {CustomMessageBox.Show("Error Connecting\nif using com0com please rename the ports to COM??"); return;}
|
||||||
|
|
||||||
|
|
||||||
string alt = "100";
|
string alt = "100";
|
||||||
|
@ -70,7 +70,7 @@ namespace ArdupilotMega
|
||||||
intalt = (int)(100 * MainV2.cs.multiplierdist);
|
intalt = (int)(100 * MainV2.cs.multiplierdist);
|
||||||
if (!int.TryParse(alt, out intalt))
|
if (!int.TryParse(alt, out intalt))
|
||||||
{
|
{
|
||||||
MessageBox.Show("Bad Alt");
|
CustomMessageBox.Show("Bad Alt");
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -43,13 +43,13 @@ namespace ArdupilotMega
|
||||||
{
|
{
|
||||||
comPort.PortName = CMB_serialport.Text;
|
comPort.PortName = CMB_serialport.Text;
|
||||||
}
|
}
|
||||||
catch { MessageBox.Show("Invalid PortName"); return; }
|
catch { CustomMessageBox.Show("Invalid PortName"); return; }
|
||||||
try {
|
try {
|
||||||
comPort.BaudRate = int.Parse(CMB_baudrate.Text);
|
comPort.BaudRate = int.Parse(CMB_baudrate.Text);
|
||||||
} catch {MessageBox.Show("Invalid BaudRate"); return;}
|
} catch {CustomMessageBox.Show("Invalid BaudRate"); return;}
|
||||||
try {
|
try {
|
||||||
comPort.Open();
|
comPort.Open();
|
||||||
} catch {MessageBox.Show("Error Connecting\nif using com0com please rename the ports to COM??"); return;}
|
} catch {CustomMessageBox.Show("Error Connecting\nif using com0com please rename the ports to COM??"); return;}
|
||||||
|
|
||||||
t12 = new System.Threading.Thread(new System.Threading.ThreadStart(mainloop))
|
t12 = new System.Threading.Thread(new System.Threading.ThreadStart(mainloop))
|
||||||
{
|
{
|
||||||
|
|
|
@ -123,13 +123,16 @@
|
||||||
this.pictureBoxQuad = new System.Windows.Forms.PictureBox();
|
this.pictureBoxQuad = new System.Windows.Forms.PictureBox();
|
||||||
this.BUT_levelac2 = new ArdupilotMega.MyButton();
|
this.BUT_levelac2 = new ArdupilotMega.MyButton();
|
||||||
this.tabHeli = new System.Windows.Forms.TabPage();
|
this.tabHeli = new System.Windows.Forms.TabPage();
|
||||||
|
this.groupBox5 = new System.Windows.Forms.GroupBox();
|
||||||
|
this.H1_ENABLE = new System.Windows.Forms.RadioButton();
|
||||||
|
this.CCPM = new System.Windows.Forms.RadioButton();
|
||||||
this.BUT_HS4save = new ArdupilotMega.MyButton();
|
this.BUT_HS4save = new ArdupilotMega.MyButton();
|
||||||
this.BUT_swash_manual = new ArdupilotMega.MyButton();
|
this.BUT_swash_manual = new ArdupilotMega.MyButton();
|
||||||
this.groupBox3 = new System.Windows.Forms.GroupBox();
|
this.groupBox3 = new System.Windows.Forms.GroupBox();
|
||||||
this.label46 = new System.Windows.Forms.Label();
|
this.label46 = new System.Windows.Forms.Label();
|
||||||
this.label45 = new System.Windows.Forms.Label();
|
this.label45 = new System.Windows.Forms.Label();
|
||||||
this.GYR_ENABLE_ = new System.Windows.Forms.CheckBox();
|
this.GYR_ENABLE = new System.Windows.Forms.CheckBox();
|
||||||
this.GYR_GAIN_ = new System.Windows.Forms.TextBox();
|
this.GYR_GAIN = new System.Windows.Forms.TextBox();
|
||||||
this.label44 = new System.Windows.Forms.Label();
|
this.label44 = new System.Windows.Forms.Label();
|
||||||
this.label43 = new System.Windows.Forms.Label();
|
this.label43 = new System.Windows.Forms.Label();
|
||||||
this.label42 = new System.Windows.Forms.Label();
|
this.label42 = new System.Windows.Forms.Label();
|
||||||
|
@ -141,9 +144,9 @@
|
||||||
this.groupBox1 = new System.Windows.Forms.GroupBox();
|
this.groupBox1 = new System.Windows.Forms.GroupBox();
|
||||||
this.label41 = new System.Windows.Forms.Label();
|
this.label41 = new System.Windows.Forms.Label();
|
||||||
this.label21 = new System.Windows.Forms.Label();
|
this.label21 = new System.Windows.Forms.Label();
|
||||||
this.COL_MIN_ = new System.Windows.Forms.TextBox();
|
this.COL_MIN = new System.Windows.Forms.TextBox();
|
||||||
this.COL_MID_ = new System.Windows.Forms.TextBox();
|
this.COL_MID = new System.Windows.Forms.TextBox();
|
||||||
this.COL_MAX_ = new System.Windows.Forms.TextBox();
|
this.COL_MAX = new System.Windows.Forms.TextBox();
|
||||||
this.BUT_0collective = new ArdupilotMega.MyButton();
|
this.BUT_0collective = new ArdupilotMega.MyButton();
|
||||||
this.HS4_TRIM = new System.Windows.Forms.NumericUpDown();
|
this.HS4_TRIM = new System.Windows.Forms.NumericUpDown();
|
||||||
this.HS3_TRIM = new System.Windows.Forms.NumericUpDown();
|
this.HS3_TRIM = new System.Windows.Forms.NumericUpDown();
|
||||||
|
@ -154,18 +157,18 @@
|
||||||
this.label37 = new System.Windows.Forms.Label();
|
this.label37 = new System.Windows.Forms.Label();
|
||||||
this.label36 = new System.Windows.Forms.Label();
|
this.label36 = new System.Windows.Forms.Label();
|
||||||
this.label26 = new System.Windows.Forms.Label();
|
this.label26 = new System.Windows.Forms.Label();
|
||||||
this.PIT_MAX_ = new System.Windows.Forms.TextBox();
|
this.PIT_MAX = new System.Windows.Forms.TextBox();
|
||||||
this.label25 = new System.Windows.Forms.Label();
|
this.label25 = new System.Windows.Forms.Label();
|
||||||
this.ROL_MAX_ = new System.Windows.Forms.TextBox();
|
this.ROL_MAX = new System.Windows.Forms.TextBox();
|
||||||
this.label23 = new System.Windows.Forms.Label();
|
this.label23 = new System.Windows.Forms.Label();
|
||||||
this.label22 = new System.Windows.Forms.Label();
|
this.label22 = new System.Windows.Forms.Label();
|
||||||
this.HS4_REV = new System.Windows.Forms.CheckBox();
|
this.HS4_REV = new System.Windows.Forms.CheckBox();
|
||||||
this.label20 = new System.Windows.Forms.Label();
|
this.label20 = new System.Windows.Forms.Label();
|
||||||
this.label19 = new System.Windows.Forms.Label();
|
this.label19 = new System.Windows.Forms.Label();
|
||||||
this.label18 = new System.Windows.Forms.Label();
|
this.label18 = new System.Windows.Forms.Label();
|
||||||
this.SV3_POS_ = new System.Windows.Forms.TextBox();
|
this.SV3_POS = new System.Windows.Forms.TextBox();
|
||||||
this.SV2_POS_ = new System.Windows.Forms.TextBox();
|
this.SV2_POS = new System.Windows.Forms.TextBox();
|
||||||
this.SV1_POS_ = new System.Windows.Forms.TextBox();
|
this.SV1_POS = new System.Windows.Forms.TextBox();
|
||||||
this.HS3_REV = new System.Windows.Forms.CheckBox();
|
this.HS3_REV = new System.Windows.Forms.CheckBox();
|
||||||
this.HS2_REV = new System.Windows.Forms.CheckBox();
|
this.HS2_REV = new System.Windows.Forms.CheckBox();
|
||||||
this.HS1_REV = new System.Windows.Forms.CheckBox();
|
this.HS1_REV = new System.Windows.Forms.CheckBox();
|
||||||
|
@ -176,6 +179,7 @@
|
||||||
this.tabReset = new System.Windows.Forms.TabPage();
|
this.tabReset = new System.Windows.Forms.TabPage();
|
||||||
this.BUT_reset = new ArdupilotMega.MyButton();
|
this.BUT_reset = new ArdupilotMega.MyButton();
|
||||||
this.toolTip1 = new System.Windows.Forms.ToolTip(this.components);
|
this.toolTip1 = new System.Windows.Forms.ToolTip(this.components);
|
||||||
|
this.BUT_MagCalibration = new ArdupilotMega.MyButton();
|
||||||
this.tabControl1.SuspendLayout();
|
this.tabControl1.SuspendLayout();
|
||||||
this.tabRadioIn.SuspendLayout();
|
this.tabRadioIn.SuspendLayout();
|
||||||
this.groupBoxElevons.SuspendLayout();
|
this.groupBoxElevons.SuspendLayout();
|
||||||
|
@ -193,6 +197,7 @@
|
||||||
((System.ComponentModel.ISupportInitialize)(this.pictureBoxQuadX)).BeginInit();
|
((System.ComponentModel.ISupportInitialize)(this.pictureBoxQuadX)).BeginInit();
|
||||||
((System.ComponentModel.ISupportInitialize)(this.pictureBoxQuad)).BeginInit();
|
((System.ComponentModel.ISupportInitialize)(this.pictureBoxQuad)).BeginInit();
|
||||||
this.tabHeli.SuspendLayout();
|
this.tabHeli.SuspendLayout();
|
||||||
|
this.groupBox5.SuspendLayout();
|
||||||
this.groupBox3.SuspendLayout();
|
this.groupBox3.SuspendLayout();
|
||||||
this.groupBox2.SuspendLayout();
|
this.groupBox2.SuspendLayout();
|
||||||
this.groupBox1.SuspendLayout();
|
this.groupBox1.SuspendLayout();
|
||||||
|
@ -405,7 +410,7 @@
|
||||||
this.BARthrottle.minline = 0;
|
this.BARthrottle.minline = 0;
|
||||||
this.BARthrottle.Name = "BARthrottle";
|
this.BARthrottle.Name = "BARthrottle";
|
||||||
this.BARthrottle.Value = 1000;
|
this.BARthrottle.Value = 1000;
|
||||||
this.BARthrottle.ValueColor = System.Drawing.Color.FromArgb(((int)(((byte)(148)))), ((int)(((byte)(193)))), ((int)(((byte)(31)))));
|
this.BARthrottle.ValueColor = System.Drawing.Color.Magenta;
|
||||||
//
|
//
|
||||||
// BARyaw
|
// BARyaw
|
||||||
//
|
//
|
||||||
|
@ -652,7 +657,8 @@
|
||||||
//
|
//
|
||||||
// tabHardware
|
// tabHardware
|
||||||
//
|
//
|
||||||
this.tabHardware.BackColor = System.Drawing.Color.DarkRed;
|
this.tabHardware.BackColor = System.Drawing.SystemColors.Control;
|
||||||
|
this.tabHardware.Controls.Add(this.BUT_MagCalibration);
|
||||||
this.tabHardware.Controls.Add(this.label27);
|
this.tabHardware.Controls.Add(this.label27);
|
||||||
this.tabHardware.Controls.Add(this.CMB_sonartype);
|
this.tabHardware.Controls.Add(this.CMB_sonartype);
|
||||||
this.tabHardware.Controls.Add(this.CHK_enableoptflow);
|
this.tabHardware.Controls.Add(this.CHK_enableoptflow);
|
||||||
|
@ -972,6 +978,7 @@
|
||||||
//
|
//
|
||||||
// tabHeli
|
// tabHeli
|
||||||
//
|
//
|
||||||
|
this.tabHeli.Controls.Add(this.groupBox5);
|
||||||
this.tabHeli.Controls.Add(this.BUT_HS4save);
|
this.tabHeli.Controls.Add(this.BUT_HS4save);
|
||||||
this.tabHeli.Controls.Add(this.BUT_swash_manual);
|
this.tabHeli.Controls.Add(this.BUT_swash_manual);
|
||||||
this.tabHeli.Controls.Add(this.groupBox3);
|
this.tabHeli.Controls.Add(this.groupBox3);
|
||||||
|
@ -989,18 +996,18 @@
|
||||||
this.tabHeli.Controls.Add(this.label37);
|
this.tabHeli.Controls.Add(this.label37);
|
||||||
this.tabHeli.Controls.Add(this.label36);
|
this.tabHeli.Controls.Add(this.label36);
|
||||||
this.tabHeli.Controls.Add(this.label26);
|
this.tabHeli.Controls.Add(this.label26);
|
||||||
this.tabHeli.Controls.Add(this.PIT_MAX_);
|
this.tabHeli.Controls.Add(this.PIT_MAX);
|
||||||
this.tabHeli.Controls.Add(this.label25);
|
this.tabHeli.Controls.Add(this.label25);
|
||||||
this.tabHeli.Controls.Add(this.ROL_MAX_);
|
this.tabHeli.Controls.Add(this.ROL_MAX);
|
||||||
this.tabHeli.Controls.Add(this.label23);
|
this.tabHeli.Controls.Add(this.label23);
|
||||||
this.tabHeli.Controls.Add(this.label22);
|
this.tabHeli.Controls.Add(this.label22);
|
||||||
this.tabHeli.Controls.Add(this.HS4_REV);
|
this.tabHeli.Controls.Add(this.HS4_REV);
|
||||||
this.tabHeli.Controls.Add(this.label20);
|
this.tabHeli.Controls.Add(this.label20);
|
||||||
this.tabHeli.Controls.Add(this.label19);
|
this.tabHeli.Controls.Add(this.label19);
|
||||||
this.tabHeli.Controls.Add(this.label18);
|
this.tabHeli.Controls.Add(this.label18);
|
||||||
this.tabHeli.Controls.Add(this.SV3_POS_);
|
this.tabHeli.Controls.Add(this.SV3_POS);
|
||||||
this.tabHeli.Controls.Add(this.SV2_POS_);
|
this.tabHeli.Controls.Add(this.SV2_POS);
|
||||||
this.tabHeli.Controls.Add(this.SV1_POS_);
|
this.tabHeli.Controls.Add(this.SV1_POS);
|
||||||
this.tabHeli.Controls.Add(this.HS3_REV);
|
this.tabHeli.Controls.Add(this.HS3_REV);
|
||||||
this.tabHeli.Controls.Add(this.HS2_REV);
|
this.tabHeli.Controls.Add(this.HS2_REV);
|
||||||
this.tabHeli.Controls.Add(this.HS1_REV);
|
this.tabHeli.Controls.Add(this.HS1_REV);
|
||||||
|
@ -1013,6 +1020,29 @@
|
||||||
this.tabHeli.UseVisualStyleBackColor = true;
|
this.tabHeli.UseVisualStyleBackColor = true;
|
||||||
this.tabHeli.Click += new System.EventHandler(this.tabHeli_Click);
|
this.tabHeli.Click += new System.EventHandler(this.tabHeli_Click);
|
||||||
//
|
//
|
||||||
|
// groupBox5
|
||||||
|
//
|
||||||
|
this.groupBox5.Controls.Add(this.H1_ENABLE);
|
||||||
|
this.groupBox5.Controls.Add(this.CCPM);
|
||||||
|
resources.ApplyResources(this.groupBox5, "groupBox5");
|
||||||
|
this.groupBox5.Name = "groupBox5";
|
||||||
|
this.groupBox5.TabStop = false;
|
||||||
|
//
|
||||||
|
// H1_ENABLE
|
||||||
|
//
|
||||||
|
resources.ApplyResources(this.H1_ENABLE, "H1_ENABLE");
|
||||||
|
this.H1_ENABLE.Name = "H1_ENABLE";
|
||||||
|
this.H1_ENABLE.TabStop = true;
|
||||||
|
this.H1_ENABLE.UseVisualStyleBackColor = true;
|
||||||
|
this.H1_ENABLE.CheckedChanged += new System.EventHandler(this.H1_ENABLE_CheckedChanged);
|
||||||
|
//
|
||||||
|
// CCPM
|
||||||
|
//
|
||||||
|
resources.ApplyResources(this.CCPM, "CCPM");
|
||||||
|
this.CCPM.Name = "CCPM";
|
||||||
|
this.CCPM.TabStop = true;
|
||||||
|
this.CCPM.UseVisualStyleBackColor = true;
|
||||||
|
//
|
||||||
// BUT_HS4save
|
// BUT_HS4save
|
||||||
//
|
//
|
||||||
resources.ApplyResources(this.BUT_HS4save, "BUT_HS4save");
|
resources.ApplyResources(this.BUT_HS4save, "BUT_HS4save");
|
||||||
|
@ -1031,8 +1061,8 @@
|
||||||
//
|
//
|
||||||
this.groupBox3.Controls.Add(this.label46);
|
this.groupBox3.Controls.Add(this.label46);
|
||||||
this.groupBox3.Controls.Add(this.label45);
|
this.groupBox3.Controls.Add(this.label45);
|
||||||
this.groupBox3.Controls.Add(this.GYR_ENABLE_);
|
this.groupBox3.Controls.Add(this.GYR_ENABLE);
|
||||||
this.groupBox3.Controls.Add(this.GYR_GAIN_);
|
this.groupBox3.Controls.Add(this.GYR_GAIN);
|
||||||
resources.ApplyResources(this.groupBox3, "groupBox3");
|
resources.ApplyResources(this.groupBox3, "groupBox3");
|
||||||
this.groupBox3.Name = "groupBox3";
|
this.groupBox3.Name = "groupBox3";
|
||||||
this.groupBox3.TabStop = false;
|
this.groupBox3.TabStop = false;
|
||||||
|
@ -1047,18 +1077,18 @@
|
||||||
resources.ApplyResources(this.label45, "label45");
|
resources.ApplyResources(this.label45, "label45");
|
||||||
this.label45.Name = "label45";
|
this.label45.Name = "label45";
|
||||||
//
|
//
|
||||||
// GYR_ENABLE_
|
// GYR_ENABLE
|
||||||
//
|
//
|
||||||
resources.ApplyResources(this.GYR_ENABLE_, "GYR_ENABLE_");
|
resources.ApplyResources(this.GYR_ENABLE, "GYR_ENABLE");
|
||||||
this.GYR_ENABLE_.Name = "GYR_ENABLE_";
|
this.GYR_ENABLE.Name = "GYR_ENABLE";
|
||||||
this.GYR_ENABLE_.UseVisualStyleBackColor = true;
|
this.GYR_ENABLE.UseVisualStyleBackColor = true;
|
||||||
this.GYR_ENABLE_.CheckedChanged += new System.EventHandler(this.GYR_ENABLE__CheckedChanged);
|
this.GYR_ENABLE.CheckedChanged += new System.EventHandler(this.GYR_ENABLE__CheckedChanged);
|
||||||
//
|
//
|
||||||
// GYR_GAIN_
|
// GYR_GAIN
|
||||||
//
|
//
|
||||||
resources.ApplyResources(this.GYR_GAIN_, "GYR_GAIN_");
|
resources.ApplyResources(this.GYR_GAIN, "GYR_GAIN");
|
||||||
this.GYR_GAIN_.Name = "GYR_GAIN_";
|
this.GYR_GAIN.Name = "GYR_GAIN";
|
||||||
this.GYR_GAIN_.Validating += new System.ComponentModel.CancelEventHandler(this.GYR_GAIN__Validating);
|
this.GYR_GAIN.Validating += new System.ComponentModel.CancelEventHandler(this.GYR_GAIN__Validating);
|
||||||
//
|
//
|
||||||
// label44
|
// label44
|
||||||
//
|
//
|
||||||
|
@ -1115,9 +1145,9 @@
|
||||||
//
|
//
|
||||||
this.groupBox1.Controls.Add(this.label41);
|
this.groupBox1.Controls.Add(this.label41);
|
||||||
this.groupBox1.Controls.Add(this.label21);
|
this.groupBox1.Controls.Add(this.label21);
|
||||||
this.groupBox1.Controls.Add(this.COL_MIN_);
|
this.groupBox1.Controls.Add(this.COL_MIN);
|
||||||
this.groupBox1.Controls.Add(this.COL_MID_);
|
this.groupBox1.Controls.Add(this.COL_MID);
|
||||||
this.groupBox1.Controls.Add(this.COL_MAX_);
|
this.groupBox1.Controls.Add(this.COL_MAX);
|
||||||
this.groupBox1.Controls.Add(this.BUT_0collective);
|
this.groupBox1.Controls.Add(this.BUT_0collective);
|
||||||
resources.ApplyResources(this.groupBox1, "groupBox1");
|
resources.ApplyResources(this.groupBox1, "groupBox1");
|
||||||
this.groupBox1.Name = "groupBox1";
|
this.groupBox1.Name = "groupBox1";
|
||||||
|
@ -1133,27 +1163,27 @@
|
||||||
resources.ApplyResources(this.label21, "label21");
|
resources.ApplyResources(this.label21, "label21");
|
||||||
this.label21.Name = "label21";
|
this.label21.Name = "label21";
|
||||||
//
|
//
|
||||||
// COL_MIN_
|
// COL_MIN
|
||||||
//
|
//
|
||||||
resources.ApplyResources(this.COL_MIN_, "COL_MIN_");
|
resources.ApplyResources(this.COL_MIN, "COL_MIN");
|
||||||
this.COL_MIN_.Name = "COL_MIN_";
|
this.COL_MIN.Name = "COL_MIN";
|
||||||
this.COL_MIN_.Enter += new System.EventHandler(this.COL_MIN__Enter);
|
this.COL_MIN.Enter += new System.EventHandler(this.COL_MIN__Enter);
|
||||||
this.COL_MIN_.Leave += new System.EventHandler(this.COL_MIN__Leave);
|
this.COL_MIN.Leave += new System.EventHandler(this.COL_MIN__Leave);
|
||||||
this.COL_MIN_.Validating += new System.ComponentModel.CancelEventHandler(this.PWM_Validating);
|
this.COL_MIN.Validating += new System.ComponentModel.CancelEventHandler(this.PWM_Validating);
|
||||||
//
|
//
|
||||||
// COL_MID_
|
// COL_MID
|
||||||
//
|
//
|
||||||
resources.ApplyResources(this.COL_MID_, "COL_MID_");
|
resources.ApplyResources(this.COL_MID, "COL_MID");
|
||||||
this.COL_MID_.Name = "COL_MID_";
|
this.COL_MID.Name = "COL_MID";
|
||||||
this.COL_MID_.Validating += new System.ComponentModel.CancelEventHandler(this.PWM_Validating);
|
this.COL_MID.Validating += new System.ComponentModel.CancelEventHandler(this.PWM_Validating);
|
||||||
//
|
//
|
||||||
// COL_MAX_
|
// COL_MAX
|
||||||
//
|
//
|
||||||
resources.ApplyResources(this.COL_MAX_, "COL_MAX_");
|
resources.ApplyResources(this.COL_MAX, "COL_MAX");
|
||||||
this.COL_MAX_.Name = "COL_MAX_";
|
this.COL_MAX.Name = "COL_MAX";
|
||||||
this.COL_MAX_.Enter += new System.EventHandler(this.COL_MAX__Enter);
|
this.COL_MAX.Enter += new System.EventHandler(this.COL_MAX__Enter);
|
||||||
this.COL_MAX_.Leave += new System.EventHandler(this.COL_MAX__Leave);
|
this.COL_MAX.Leave += new System.EventHandler(this.COL_MAX__Leave);
|
||||||
this.COL_MAX_.Validating += new System.ComponentModel.CancelEventHandler(this.PWM_Validating);
|
this.COL_MAX.Validating += new System.ComponentModel.CancelEventHandler(this.PWM_Validating);
|
||||||
//
|
//
|
||||||
// BUT_0collective
|
// BUT_0collective
|
||||||
//
|
//
|
||||||
|
@ -1271,22 +1301,22 @@
|
||||||
resources.ApplyResources(this.label26, "label26");
|
resources.ApplyResources(this.label26, "label26");
|
||||||
this.label26.Name = "label26";
|
this.label26.Name = "label26";
|
||||||
//
|
//
|
||||||
// PIT_MAX_
|
// PIT_MAX
|
||||||
//
|
//
|
||||||
resources.ApplyResources(this.PIT_MAX_, "PIT_MAX_");
|
resources.ApplyResources(this.PIT_MAX, "PIT_MAX");
|
||||||
this.PIT_MAX_.Name = "PIT_MAX_";
|
this.PIT_MAX.Name = "PIT_MAX";
|
||||||
this.PIT_MAX_.Validating += new System.ComponentModel.CancelEventHandler(this.PIT_MAX__Validating);
|
this.PIT_MAX.Validating += new System.ComponentModel.CancelEventHandler(this.PIT_MAX__Validating);
|
||||||
//
|
//
|
||||||
// label25
|
// label25
|
||||||
//
|
//
|
||||||
resources.ApplyResources(this.label25, "label25");
|
resources.ApplyResources(this.label25, "label25");
|
||||||
this.label25.Name = "label25";
|
this.label25.Name = "label25";
|
||||||
//
|
//
|
||||||
// ROL_MAX_
|
// ROL_MAX
|
||||||
//
|
//
|
||||||
resources.ApplyResources(this.ROL_MAX_, "ROL_MAX_");
|
resources.ApplyResources(this.ROL_MAX, "ROL_MAX");
|
||||||
this.ROL_MAX_.Name = "ROL_MAX_";
|
this.ROL_MAX.Name = "ROL_MAX";
|
||||||
this.ROL_MAX_.Validating += new System.ComponentModel.CancelEventHandler(this.ROL_MAX__Validating);
|
this.ROL_MAX.Validating += new System.ComponentModel.CancelEventHandler(this.ROL_MAX__Validating);
|
||||||
//
|
//
|
||||||
// label23
|
// label23
|
||||||
//
|
//
|
||||||
|
@ -1320,23 +1350,23 @@
|
||||||
resources.ApplyResources(this.label18, "label18");
|
resources.ApplyResources(this.label18, "label18");
|
||||||
this.label18.Name = "label18";
|
this.label18.Name = "label18";
|
||||||
//
|
//
|
||||||
// SV3_POS_
|
// SV3_POS
|
||||||
//
|
//
|
||||||
resources.ApplyResources(this.SV3_POS_, "SV3_POS_");
|
resources.ApplyResources(this.SV3_POS, "SV3_POS");
|
||||||
this.SV3_POS_.Name = "SV3_POS_";
|
this.SV3_POS.Name = "SV3_POS";
|
||||||
this.SV3_POS_.Validating += new System.ComponentModel.CancelEventHandler(this.TXT_srvpos3_Validating);
|
this.SV3_POS.Validating += new System.ComponentModel.CancelEventHandler(this.TXT_srvpos3_Validating);
|
||||||
//
|
//
|
||||||
// SV2_POS_
|
// SV2_POS
|
||||||
//
|
//
|
||||||
resources.ApplyResources(this.SV2_POS_, "SV2_POS_");
|
resources.ApplyResources(this.SV2_POS, "SV2_POS");
|
||||||
this.SV2_POS_.Name = "SV2_POS_";
|
this.SV2_POS.Name = "SV2_POS";
|
||||||
this.SV2_POS_.Validating += new System.ComponentModel.CancelEventHandler(this.TXT_srvpos2_Validating);
|
this.SV2_POS.Validating += new System.ComponentModel.CancelEventHandler(this.TXT_srvpos2_Validating);
|
||||||
//
|
//
|
||||||
// SV1_POS_
|
// SV1_POS
|
||||||
//
|
//
|
||||||
resources.ApplyResources(this.SV1_POS_, "SV1_POS_");
|
resources.ApplyResources(this.SV1_POS, "SV1_POS");
|
||||||
this.SV1_POS_.Name = "SV1_POS_";
|
this.SV1_POS.Name = "SV1_POS";
|
||||||
this.SV1_POS_.Validating += new System.ComponentModel.CancelEventHandler(this.TXT_srvpos1_Validating);
|
this.SV1_POS.Validating += new System.ComponentModel.CancelEventHandler(this.TXT_srvpos1_Validating);
|
||||||
//
|
//
|
||||||
// HS3_REV
|
// HS3_REV
|
||||||
//
|
//
|
||||||
|
@ -1554,6 +1584,13 @@
|
||||||
this.BUT_reset.UseVisualStyleBackColor = true;
|
this.BUT_reset.UseVisualStyleBackColor = true;
|
||||||
this.BUT_reset.Click += new System.EventHandler(this.BUT_reset_Click);
|
this.BUT_reset.Click += new System.EventHandler(this.BUT_reset_Click);
|
||||||
//
|
//
|
||||||
|
// BUT_MagCalibration
|
||||||
|
//
|
||||||
|
resources.ApplyResources(this.BUT_MagCalibration, "BUT_MagCalibration");
|
||||||
|
this.BUT_MagCalibration.Name = "BUT_MagCalibration";
|
||||||
|
this.BUT_MagCalibration.UseVisualStyleBackColor = true;
|
||||||
|
this.BUT_MagCalibration.Click += new System.EventHandler(this.BUT_MagCalibration_Click);
|
||||||
|
//
|
||||||
// Setup
|
// Setup
|
||||||
//
|
//
|
||||||
resources.ApplyResources(this, "$this");
|
resources.ApplyResources(this, "$this");
|
||||||
|
@ -1588,6 +1625,8 @@
|
||||||
((System.ComponentModel.ISupportInitialize)(this.pictureBoxQuad)).EndInit();
|
((System.ComponentModel.ISupportInitialize)(this.pictureBoxQuad)).EndInit();
|
||||||
this.tabHeli.ResumeLayout(false);
|
this.tabHeli.ResumeLayout(false);
|
||||||
this.tabHeli.PerformLayout();
|
this.tabHeli.PerformLayout();
|
||||||
|
this.groupBox5.ResumeLayout(false);
|
||||||
|
this.groupBox5.PerformLayout();
|
||||||
this.groupBox3.ResumeLayout(false);
|
this.groupBox3.ResumeLayout(false);
|
||||||
this.groupBox3.PerformLayout();
|
this.groupBox3.PerformLayout();
|
||||||
this.groupBox2.ResumeLayout(false);
|
this.groupBox2.ResumeLayout(false);
|
||||||
|
@ -1666,9 +1705,9 @@
|
||||||
private System.Windows.Forms.Label label20;
|
private System.Windows.Forms.Label label20;
|
||||||
private System.Windows.Forms.Label label19;
|
private System.Windows.Forms.Label label19;
|
||||||
private System.Windows.Forms.Label label18;
|
private System.Windows.Forms.Label label18;
|
||||||
private System.Windows.Forms.TextBox SV3_POS_;
|
private System.Windows.Forms.TextBox SV3_POS;
|
||||||
private System.Windows.Forms.TextBox SV2_POS_;
|
private System.Windows.Forms.TextBox SV2_POS;
|
||||||
private System.Windows.Forms.TextBox SV1_POS_;
|
private System.Windows.Forms.TextBox SV1_POS;
|
||||||
private System.Windows.Forms.CheckBox HS4_REV;
|
private System.Windows.Forms.CheckBox HS4_REV;
|
||||||
private System.Windows.Forms.Label label22;
|
private System.Windows.Forms.Label label22;
|
||||||
private System.Windows.Forms.Label label23;
|
private System.Windows.Forms.Label label23;
|
||||||
|
@ -1676,11 +1715,11 @@
|
||||||
private VerticalProgressBar2 HS3;
|
private VerticalProgressBar2 HS3;
|
||||||
private MyButton BUT_0collective;
|
private MyButton BUT_0collective;
|
||||||
private System.Windows.Forms.Label label25;
|
private System.Windows.Forms.Label label25;
|
||||||
private System.Windows.Forms.TextBox ROL_MAX_;
|
private System.Windows.Forms.TextBox ROL_MAX;
|
||||||
private System.Windows.Forms.Label label26;
|
private System.Windows.Forms.Label label26;
|
||||||
private System.Windows.Forms.TextBox PIT_MAX_;
|
private System.Windows.Forms.TextBox PIT_MAX;
|
||||||
private System.Windows.Forms.TextBox GYR_GAIN_;
|
private System.Windows.Forms.TextBox GYR_GAIN;
|
||||||
private System.Windows.Forms.CheckBox GYR_ENABLE_;
|
private System.Windows.Forms.CheckBox GYR_ENABLE;
|
||||||
private System.Windows.Forms.Label label28;
|
private System.Windows.Forms.Label label28;
|
||||||
private MyButton BUT_levelac2;
|
private MyButton BUT_levelac2;
|
||||||
private System.Windows.Forms.ToolTip toolTip1;
|
private System.Windows.Forms.ToolTip toolTip1;
|
||||||
|
@ -1722,9 +1761,9 @@
|
||||||
private System.Windows.Forms.NumericUpDown HS4_TRIM;
|
private System.Windows.Forms.NumericUpDown HS4_TRIM;
|
||||||
private System.Windows.Forms.GroupBox groupBox1;
|
private System.Windows.Forms.GroupBox groupBox1;
|
||||||
private MyButton BUT_swash_manual;
|
private MyButton BUT_swash_manual;
|
||||||
private System.Windows.Forms.TextBox COL_MIN_;
|
private System.Windows.Forms.TextBox COL_MIN;
|
||||||
private System.Windows.Forms.TextBox COL_MID_;
|
private System.Windows.Forms.TextBox COL_MID;
|
||||||
private System.Windows.Forms.TextBox COL_MAX_;
|
private System.Windows.Forms.TextBox COL_MAX;
|
||||||
private System.Windows.Forms.Label label41;
|
private System.Windows.Forms.Label label41;
|
||||||
private System.Windows.Forms.Label label21;
|
private System.Windows.Forms.Label label21;
|
||||||
private MyButton BUT_HS4save;
|
private MyButton BUT_HS4save;
|
||||||
|
@ -1751,6 +1790,10 @@
|
||||||
private System.Windows.Forms.ComboBox CMB_batmonsensortype;
|
private System.Windows.Forms.ComboBox CMB_batmonsensortype;
|
||||||
private System.Windows.Forms.Label label47;
|
private System.Windows.Forms.Label label47;
|
||||||
private System.Windows.Forms.GroupBox groupBox4;
|
private System.Windows.Forms.GroupBox groupBox4;
|
||||||
|
private System.Windows.Forms.GroupBox groupBox5;
|
||||||
|
private System.Windows.Forms.RadioButton H1_ENABLE;
|
||||||
|
private System.Windows.Forms.RadioButton CCPM;
|
||||||
|
private MyButton BUT_MagCalibration;
|
||||||
|
|
||||||
}
|
}
|
||||||
}
|
}
|
|
@ -58,8 +58,29 @@ namespace ArdupilotMega.Setup
|
||||||
|
|
||||||
if (MainV2.cs.firmware == MainV2.Firmwares.ArduPlane) // APM
|
if (MainV2.cs.firmware == MainV2.Firmwares.ArduPlane) // APM
|
||||||
{
|
{
|
||||||
pwm = MainV2.cs.ch8in;
|
if (MainV2.comPort.param.ContainsKey("FLTMODE_CH"))
|
||||||
LBL_flightmodepwm.Text = "8: " + MainV2.cs.ch8in.ToString();
|
{
|
||||||
|
switch ((int)(float)MainV2.comPort.param["FLTMODE_CH"])
|
||||||
|
{
|
||||||
|
case 5:
|
||||||
|
pwm = MainV2.cs.ch5in;
|
||||||
|
break;
|
||||||
|
case 6:
|
||||||
|
pwm = MainV2.cs.ch6in;
|
||||||
|
break;
|
||||||
|
case 7:
|
||||||
|
pwm = MainV2.cs.ch7in;
|
||||||
|
break;
|
||||||
|
case 8:
|
||||||
|
pwm = MainV2.cs.ch8in;
|
||||||
|
break;
|
||||||
|
default:
|
||||||
|
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
|
LBL_flightmodepwm.Text = MainV2.comPort.param["FLTMODE_CH"].ToString() + ": " + pwm.ToString();
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
if (MainV2.cs.firmware == MainV2.Firmwares.ArduCopter2) // ac2
|
if (MainV2.cs.firmware == MainV2.Firmwares.ArduCopter2) // ac2
|
||||||
|
@ -105,8 +126,8 @@ namespace ArdupilotMega.Setup
|
||||||
{
|
{
|
||||||
try
|
try
|
||||||
{
|
{
|
||||||
HS3.minline = int.Parse(COL_MIN_.Text);
|
HS3.minline = int.Parse(COL_MIN.Text);
|
||||||
HS3.maxline = int.Parse(COL_MAX_.Text);
|
HS3.maxline = int.Parse(COL_MAX.Text);
|
||||||
HS4.maxline = int.Parse(HS4_MIN.Text);
|
HS4.maxline = int.Parse(HS4_MIN.Text);
|
||||||
HS4.minline = int.Parse(HS4_MAX.Text);
|
HS4.minline = int.Parse(HS4_MAX.Text);
|
||||||
}
|
}
|
||||||
|
@ -138,7 +159,7 @@ namespace ArdupilotMega.Setup
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
MessageBox.Show("Ensure your transmitter is on and receiver is powered and connected\nEnsure your motor does not have power/no props!!!");
|
CustomMessageBox.Show("Ensure your transmitter is on and receiver is powered and connected\nEnsure your motor does not have power/no props!!!");
|
||||||
|
|
||||||
byte oldrc = MainV2.cs.raterc;
|
byte oldrc = MainV2.cs.raterc;
|
||||||
byte oldatt = MainV2.cs.rateattitude;
|
byte oldatt = MainV2.cs.rateattitude;
|
||||||
|
@ -224,7 +245,7 @@ namespace ArdupilotMega.Setup
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
MessageBox.Show("Ensure all your sticks are centered and throttle is down, and click ok to continue");
|
CustomMessageBox.Show("Ensure all your sticks are centered and throttle is down, and click ok to continue");
|
||||||
|
|
||||||
MainV2.cs.UpdateCurrentSettings(currentStateBindingSource, true, MainV2.comPort);
|
MainV2.cs.UpdateCurrentSettings(currentStateBindingSource, true, MainV2.comPort);
|
||||||
|
|
||||||
|
@ -253,7 +274,7 @@ namespace ArdupilotMega.Setup
|
||||||
if (rctrim[a] < 1195 || rctrim[a] > 1205)
|
if (rctrim[a] < 1195 || rctrim[a] > 1205)
|
||||||
MainV2.comPort.setParam("RC" + (a + 1).ToString("0") + "_TRIM", rctrim[a]);
|
MainV2.comPort.setParam("RC" + (a + 1).ToString("0") + "_TRIM", rctrim[a]);
|
||||||
}
|
}
|
||||||
catch { MessageBox.Show("Failed to set Channel " + (a + 1).ToString()); }
|
catch { CustomMessageBox.Show("Failed to set Channel " + (a + 1).ToString()); }
|
||||||
|
|
||||||
data = data + "CH" + (a + 1) + " " + rcmin[a] + " | " + rcmax[a] + "\n";
|
data = data + "CH" + (a + 1) + " " + rcmin[a] + " | " + rcmax[a] + "\n";
|
||||||
}
|
}
|
||||||
|
@ -278,7 +299,7 @@ namespace ArdupilotMega.Setup
|
||||||
Configuration.startup = false;
|
Configuration.startup = false;
|
||||||
}
|
}
|
||||||
|
|
||||||
MessageBox.Show("Here are the detected radio options\nNOTE Channels not connected are displayed as 1500 +-2\nNormal values are around 1100 | 1900\nChannel:Min | Max \n" + data, "Radio");
|
CustomMessageBox.Show("Here are the detected radio options\nNOTE Channels not connected are displayed as 1500 +-2\nNormal values are around 1100 | 1900\nChannel:Min | Max \n" + data, "Radio");
|
||||||
|
|
||||||
BUT_Calibrateradio.Text = "Please goto the next tab";
|
BUT_Calibrateradio.Text = "Please goto the next tab";
|
||||||
}
|
}
|
||||||
|
@ -315,7 +336,7 @@ namespace ArdupilotMega.Setup
|
||||||
CHK_revch3.Checked = MainV2.comPort.param["RC3_REV"].ToString() == "-1";
|
CHK_revch3.Checked = MainV2.comPort.param["RC3_REV"].ToString() == "-1";
|
||||||
CHK_revch4.Checked = MainV2.comPort.param["RC4_REV"].ToString() == "-1";
|
CHK_revch4.Checked = MainV2.comPort.param["RC4_REV"].ToString() == "-1";
|
||||||
}
|
}
|
||||||
catch (Exception ex) { MessageBox.Show("Missing RC rev Param "+ex.ToString()); }
|
catch (Exception ex) { CustomMessageBox.Show("Missing RC rev Param "+ex.ToString()); }
|
||||||
startup = false;
|
startup = false;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -584,7 +605,7 @@ namespace ArdupilotMega.Setup
|
||||||
MainV2.comPort.setParam("SIMPLE", value);
|
MainV2.comPort.setParam("SIMPLE", value);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
catch { MessageBox.Show("Failed to set Flight modes"); }
|
catch { CustomMessageBox.Show("Failed to set Flight modes"); }
|
||||||
BUT_SaveModes.Text = "Complete";
|
BUT_SaveModes.Text = "Complete";
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -614,7 +635,7 @@ namespace ArdupilotMega.Setup
|
||||||
{
|
{
|
||||||
if (MainV2.comPort.param["COMPASS_DEC"] == null)
|
if (MainV2.comPort.param["COMPASS_DEC"] == null)
|
||||||
{
|
{
|
||||||
MessageBox.Show("Not Available");
|
CustomMessageBox.Show("Not Available");
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
|
@ -634,14 +655,14 @@ namespace ArdupilotMega.Setup
|
||||||
dec -= ((mins) / 60.0f);
|
dec -= ((mins) / 60.0f);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
catch { MessageBox.Show("Invalid input!"); return; }
|
catch { CustomMessageBox.Show("Invalid input!"); return; }
|
||||||
|
|
||||||
TXT_declination.Text = dec.ToString();
|
TXT_declination.Text = dec.ToString();
|
||||||
|
|
||||||
MainV2.comPort.setParam("COMPASS_DEC", dec * deg2rad);
|
MainV2.comPort.setParam("COMPASS_DEC", dec * deg2rad);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
catch { MessageBox.Show("Set COMPASS_DEC Failed"); }
|
catch { CustomMessageBox.Show("Set COMPASS_DEC Failed"); }
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
@ -653,14 +674,14 @@ namespace ArdupilotMega.Setup
|
||||||
{
|
{
|
||||||
if (MainV2.comPort.param["MAG_ENABLE"] == null)
|
if (MainV2.comPort.param["MAG_ENABLE"] == null)
|
||||||
{
|
{
|
||||||
MessageBox.Show("Not Available");
|
CustomMessageBox.Show("Not Available");
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
MainV2.comPort.setParam("MAG_ENABLE", ((CheckBox)sender).Checked == true ? 1 : 0);
|
MainV2.comPort.setParam("MAG_ENABLE", ((CheckBox)sender).Checked == true ? 1 : 0);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
catch { MessageBox.Show("Set MAG_ENABLE Failed"); }
|
catch { CustomMessageBox.Show("Set MAG_ENABLE Failed"); }
|
||||||
}
|
}
|
||||||
|
|
||||||
//((CheckBox)sender).Checked = !((CheckBox)sender).Checked;
|
//((CheckBox)sender).Checked = !((CheckBox)sender).Checked;
|
||||||
|
@ -674,14 +695,14 @@ namespace ArdupilotMega.Setup
|
||||||
{
|
{
|
||||||
if (MainV2.comPort.param["SONAR_ENABLE"] == null)
|
if (MainV2.comPort.param["SONAR_ENABLE"] == null)
|
||||||
{
|
{
|
||||||
MessageBox.Show("Not Available");
|
CustomMessageBox.Show("Not Available");
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
MainV2.comPort.setParam("SONAR_ENABLE", ((CheckBox)sender).Checked == true ? 1 : 0);
|
MainV2.comPort.setParam("SONAR_ENABLE", ((CheckBox)sender).Checked == true ? 1 : 0);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
catch { MessageBox.Show("Set SONAR_ENABLE Failed"); }
|
catch { CustomMessageBox.Show("Set SONAR_ENABLE Failed"); }
|
||||||
}
|
}
|
||||||
|
|
||||||
private void CHK_enableairspeed_CheckedChanged(object sender, EventArgs e)
|
private void CHK_enableairspeed_CheckedChanged(object sender, EventArgs e)
|
||||||
|
@ -692,14 +713,14 @@ namespace ArdupilotMega.Setup
|
||||||
{
|
{
|
||||||
if (MainV2.comPort.param["ARSPD_ENABLE"] == null)
|
if (MainV2.comPort.param["ARSPD_ENABLE"] == null)
|
||||||
{
|
{
|
||||||
MessageBox.Show("Not Available on " + MainV2.cs.firmware.ToString());
|
CustomMessageBox.Show("Not Available on " + MainV2.cs.firmware.ToString());
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
MainV2.comPort.setParam("ARSPD_ENABLE", ((CheckBox)sender).Checked == true ? 1 : 0);
|
MainV2.comPort.setParam("ARSPD_ENABLE", ((CheckBox)sender).Checked == true ? 1 : 0);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
catch { MessageBox.Show("Set ARSPD_ENABLE Failed"); }
|
catch { CustomMessageBox.Show("Set ARSPD_ENABLE Failed"); }
|
||||||
}
|
}
|
||||||
private void CHK_enablebattmon_CheckedChanged(object sender, EventArgs e)
|
private void CHK_enablebattmon_CheckedChanged(object sender, EventArgs e)
|
||||||
{
|
{
|
||||||
|
@ -717,7 +738,7 @@ namespace ArdupilotMega.Setup
|
||||||
CMB_batmontype.SelectedIndex = 1;
|
CMB_batmontype.SelectedIndex = 1;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
catch { MessageBox.Show("Set BATT_MONITOR Failed"); }
|
catch { CustomMessageBox.Show("Set BATT_MONITOR Failed"); }
|
||||||
}
|
}
|
||||||
private void TXT_battcapacity_Validating(object sender, CancelEventArgs e)
|
private void TXT_battcapacity_Validating(object sender, CancelEventArgs e)
|
||||||
{
|
{
|
||||||
|
@ -732,14 +753,14 @@ namespace ArdupilotMega.Setup
|
||||||
{
|
{
|
||||||
if (MainV2.comPort.param["BATT_CAPACITY"] == null)
|
if (MainV2.comPort.param["BATT_CAPACITY"] == null)
|
||||||
{
|
{
|
||||||
MessageBox.Show("Not Available");
|
CustomMessageBox.Show("Not Available");
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
MainV2.comPort.setParam("BATT_CAPACITY", float.Parse(TXT_battcapacity.Text));
|
MainV2.comPort.setParam("BATT_CAPACITY", float.Parse(TXT_battcapacity.Text));
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
catch { MessageBox.Show("Set BATT_CAPACITY Failed"); }
|
catch { CustomMessageBox.Show("Set BATT_CAPACITY Failed"); }
|
||||||
}
|
}
|
||||||
private void CMB_batmontype_SelectedIndexChanged(object sender, EventArgs e)
|
private void CMB_batmontype_SelectedIndexChanged(object sender, EventArgs e)
|
||||||
{
|
{
|
||||||
|
@ -749,7 +770,7 @@ namespace ArdupilotMega.Setup
|
||||||
{
|
{
|
||||||
if (MainV2.comPort.param["BATT_MONITOR"] == null)
|
if (MainV2.comPort.param["BATT_MONITOR"] == null)
|
||||||
{
|
{
|
||||||
MessageBox.Show("Not Available");
|
CustomMessageBox.Show("Not Available");
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
|
@ -783,7 +804,7 @@ namespace ArdupilotMega.Setup
|
||||||
MainV2.comPort.setParam("BATT_MONITOR", selection);
|
MainV2.comPort.setParam("BATT_MONITOR", selection);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
catch { MessageBox.Show("Set BATT_MONITOR Failed"); }
|
catch { CustomMessageBox.Show("Set BATT_MONITOR Failed"); }
|
||||||
}
|
}
|
||||||
private void TXT_inputvoltage_Validating(object sender, CancelEventArgs e)
|
private void TXT_inputvoltage_Validating(object sender, CancelEventArgs e)
|
||||||
{
|
{
|
||||||
|
@ -798,14 +819,14 @@ namespace ArdupilotMega.Setup
|
||||||
{
|
{
|
||||||
if (MainV2.comPort.param["INPUT_VOLTS"] == null)
|
if (MainV2.comPort.param["INPUT_VOLTS"] == null)
|
||||||
{
|
{
|
||||||
MessageBox.Show("Not Available");
|
CustomMessageBox.Show("Not Available");
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
MainV2.comPort.setParam("INPUT_VOLTS", float.Parse(TXT_inputvoltage.Text));
|
MainV2.comPort.setParam("INPUT_VOLTS", float.Parse(TXT_inputvoltage.Text));
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
catch { MessageBox.Show("Set INPUT_VOLTS Failed"); }
|
catch { CustomMessageBox.Show("Set INPUT_VOLTS Failed"); }
|
||||||
}
|
}
|
||||||
private void TXT_measuredvoltage_Validating(object sender, CancelEventArgs e)
|
private void TXT_measuredvoltage_Validating(object sender, CancelEventArgs e)
|
||||||
{
|
{
|
||||||
|
@ -826,20 +847,20 @@ namespace ArdupilotMega.Setup
|
||||||
float new_divider = (measuredvoltage * divider) / voltage;
|
float new_divider = (measuredvoltage * divider) / voltage;
|
||||||
TXT_divider.Text = new_divider.ToString();
|
TXT_divider.Text = new_divider.ToString();
|
||||||
}
|
}
|
||||||
catch { MessageBox.Show("Invalid number entered"); return; }
|
catch { CustomMessageBox.Show("Invalid number entered"); return; }
|
||||||
|
|
||||||
try
|
try
|
||||||
{
|
{
|
||||||
if (MainV2.comPort.param["VOLT_DIVIDER"] == null)
|
if (MainV2.comPort.param["VOLT_DIVIDER"] == null)
|
||||||
{
|
{
|
||||||
MessageBox.Show("Not Available");
|
CustomMessageBox.Show("Not Available");
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
MainV2.comPort.setParam("VOLT_DIVIDER", float.Parse(TXT_divider.Text));
|
MainV2.comPort.setParam("VOLT_DIVIDER", float.Parse(TXT_divider.Text));
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
catch { MessageBox.Show("Set VOLT_DIVIDER Failed"); }
|
catch { CustomMessageBox.Show("Set VOLT_DIVIDER Failed"); }
|
||||||
}
|
}
|
||||||
private void TXT_divider_Validating(object sender, CancelEventArgs e)
|
private void TXT_divider_Validating(object sender, CancelEventArgs e)
|
||||||
{
|
{
|
||||||
|
@ -854,14 +875,14 @@ namespace ArdupilotMega.Setup
|
||||||
{
|
{
|
||||||
if (MainV2.comPort.param["VOLT_DIVIDER"] == null)
|
if (MainV2.comPort.param["VOLT_DIVIDER"] == null)
|
||||||
{
|
{
|
||||||
MessageBox.Show("Not Available");
|
CustomMessageBox.Show("Not Available");
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
MainV2.comPort.setParam("VOLT_DIVIDER", float.Parse(TXT_divider.Text));
|
MainV2.comPort.setParam("VOLT_DIVIDER", float.Parse(TXT_divider.Text));
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
catch { MessageBox.Show("Set VOLT_DIVIDER Failed"); }
|
catch { CustomMessageBox.Show("Set VOLT_DIVIDER Failed"); }
|
||||||
}
|
}
|
||||||
private void TXT_ampspervolt_Validating(object sender, CancelEventArgs e)
|
private void TXT_ampspervolt_Validating(object sender, CancelEventArgs e)
|
||||||
{
|
{
|
||||||
|
@ -876,14 +897,14 @@ namespace ArdupilotMega.Setup
|
||||||
{
|
{
|
||||||
if (MainV2.comPort.param["AMP_PER_VOLT"] == null)
|
if (MainV2.comPort.param["AMP_PER_VOLT"] == null)
|
||||||
{
|
{
|
||||||
MessageBox.Show("Not Available");
|
CustomMessageBox.Show("Not Available");
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
MainV2.comPort.setParam("AMP_PER_VOLT", float.Parse(TXT_ampspervolt.Text));
|
MainV2.comPort.setParam("AMP_PER_VOLT", float.Parse(TXT_ampspervolt.Text));
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
catch { MessageBox.Show("Set AMP_PER_VOLT Failed"); }
|
catch { CustomMessageBox.Show("Set AMP_PER_VOLT Failed"); }
|
||||||
}
|
}
|
||||||
|
|
||||||
private void BUT_reset_Click(object sender, EventArgs e)
|
private void BUT_reset_Click(object sender, EventArgs e)
|
||||||
|
@ -892,7 +913,7 @@ namespace ArdupilotMega.Setup
|
||||||
{
|
{
|
||||||
MainV2.comPort.setParam("SYSID_SW_MREV", UInt16.MaxValue);
|
MainV2.comPort.setParam("SYSID_SW_MREV", UInt16.MaxValue);
|
||||||
}
|
}
|
||||||
catch { MessageBox.Show("Set SYSID_SW_MREV Failed"); return; }
|
catch { CustomMessageBox.Show("Set SYSID_SW_MREV Failed"); return; }
|
||||||
|
|
||||||
MainV2.givecomport = true;
|
MainV2.givecomport = true;
|
||||||
|
|
||||||
|
@ -910,7 +931,7 @@ namespace ArdupilotMega.Setup
|
||||||
comPortT.DtrEnable = true;
|
comPortT.DtrEnable = true;
|
||||||
comPortT.Open();
|
comPortT.Open();
|
||||||
}
|
}
|
||||||
catch (Exception ex) { MainV2.givecomport = false; MessageBox.Show("Invalid Comport Settings : " + ex.Message); return; }
|
catch (Exception ex) { MainV2.givecomport = false; CustomMessageBox.Show("Invalid Comport Settings : " + ex.Message); return; }
|
||||||
|
|
||||||
BUT_reset.Text = "Rebooting (17 sec)";
|
BUT_reset.Text = "Rebooting (17 sec)";
|
||||||
BUT_reset.Refresh();
|
BUT_reset.Refresh();
|
||||||
|
@ -937,7 +958,7 @@ namespace ArdupilotMega.Setup
|
||||||
}
|
}
|
||||||
catch
|
catch
|
||||||
{
|
{
|
||||||
MessageBox.Show("Failed to re-connect : Please try again");
|
CustomMessageBox.Show("Failed to re-connect : Please try again");
|
||||||
this.Close();
|
this.Close();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -964,9 +985,9 @@ namespace ArdupilotMega.Setup
|
||||||
try
|
try
|
||||||
{
|
{
|
||||||
MainV2.comPort.setParam("FRAME", 0f);
|
MainV2.comPort.setParam("FRAME", 0f);
|
||||||
MessageBox.Show("Set to +");
|
CustomMessageBox.Show("Set to +");
|
||||||
}
|
}
|
||||||
catch { MessageBox.Show("Set frame failed"); }
|
catch { CustomMessageBox.Show("Set frame failed"); }
|
||||||
}
|
}
|
||||||
|
|
||||||
private void pictureBoxQuadX_Click(object sender, EventArgs e)
|
private void pictureBoxQuadX_Click(object sender, EventArgs e)
|
||||||
|
@ -974,20 +995,22 @@ namespace ArdupilotMega.Setup
|
||||||
try
|
try
|
||||||
{
|
{
|
||||||
MainV2.comPort.setParam("FRAME", 1f);
|
MainV2.comPort.setParam("FRAME", 1f);
|
||||||
MessageBox.Show("Set to x");
|
CustomMessageBox.Show("Set to x");
|
||||||
}
|
}
|
||||||
catch { MessageBox.Show("Set frame failed"); }
|
catch { CustomMessageBox.Show("Set frame failed"); }
|
||||||
}
|
}
|
||||||
|
|
||||||
private void Setup_Load(object sender, EventArgs e)
|
private void Setup_Load(object sender, EventArgs e)
|
||||||
{
|
{
|
||||||
if (!MainV2.comPort.BaseStream.IsOpen)
|
if (!MainV2.comPort.BaseStream.IsOpen)
|
||||||
{
|
{
|
||||||
MessageBox.Show("Please Connect First");
|
CustomMessageBox.Show("Please Connect First");
|
||||||
this.Close();
|
this.Close();
|
||||||
}
|
}
|
||||||
|
else
|
||||||
tabControl1_SelectedIndexChanged(null, new EventArgs());
|
{
|
||||||
|
tabControl1_SelectedIndexChanged(null, new EventArgs());
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
private void TXT_srvpos1_Validating(object sender, CancelEventArgs e)
|
private void TXT_srvpos1_Validating(object sender, CancelEventArgs e)
|
||||||
|
@ -1010,7 +1033,7 @@ namespace ArdupilotMega.Setup
|
||||||
MainV2.comPort.setParam("HSV_MAN", 0); // randy request - last
|
MainV2.comPort.setParam("HSV_MAN", 0); // randy request - last
|
||||||
|
|
||||||
}
|
}
|
||||||
catch { MessageBox.Show("Set " + ((TextBox)sender).Name + " failed"); }
|
catch { CustomMessageBox.Show("Set " + ((TextBox)sender).Name + " failed"); }
|
||||||
}
|
}
|
||||||
|
|
||||||
private void TXT_srvpos2_Validating(object sender, CancelEventArgs e)
|
private void TXT_srvpos2_Validating(object sender, CancelEventArgs e)
|
||||||
|
@ -1032,7 +1055,7 @@ namespace ArdupilotMega.Setup
|
||||||
System.Threading.Thread.Sleep(100);
|
System.Threading.Thread.Sleep(100);
|
||||||
MainV2.comPort.setParam("HSV_MAN", 0); // randy request - last
|
MainV2.comPort.setParam("HSV_MAN", 0); // randy request - last
|
||||||
}
|
}
|
||||||
catch { MessageBox.Show("Set " + ((TextBox)sender).Name + " failed"); }
|
catch { CustomMessageBox.Show("Set " + ((TextBox)sender).Name + " failed"); }
|
||||||
}
|
}
|
||||||
|
|
||||||
private void TXT_srvpos3_Validating(object sender, CancelEventArgs e)
|
private void TXT_srvpos3_Validating(object sender, CancelEventArgs e)
|
||||||
|
@ -1054,21 +1077,21 @@ namespace ArdupilotMega.Setup
|
||||||
System.Threading.Thread.Sleep(100);
|
System.Threading.Thread.Sleep(100);
|
||||||
MainV2.comPort.setParam("HSV_MAN", 0); // randy request - last
|
MainV2.comPort.setParam("HSV_MAN", 0); // randy request - last
|
||||||
}
|
}
|
||||||
catch { MessageBox.Show("Set " + ((TextBox)sender).Name + " failed"); }
|
catch { CustomMessageBox.Show("Set " + ((TextBox)sender).Name + " failed"); }
|
||||||
}
|
}
|
||||||
|
|
||||||
private void BUT_0collective_Click(object sender, EventArgs e)
|
private void BUT_0collective_Click(object sender, EventArgs e)
|
||||||
{
|
{
|
||||||
MessageBox.Show("Make sure your blades are at 0 degrees");
|
CustomMessageBox.Show("Make sure your blades are at 0 degrees");
|
||||||
|
|
||||||
try
|
try
|
||||||
{
|
{
|
||||||
|
|
||||||
MainV2.comPort.setParam("COL_MID_", MainV2.cs.ch3in);
|
MainV2.comPort.setParam("COL_MID_", MainV2.cs.ch3in);
|
||||||
|
|
||||||
COL_MID_.Text = MainV2.comPort.param["COL_MID_"].ToString();
|
COL_MID.Text = MainV2.comPort.param["COL_MID_"].ToString();
|
||||||
}
|
}
|
||||||
catch { MessageBox.Show("Set COL_MID_ failed"); }
|
catch { CustomMessageBox.Show("Set COL_MID_ failed"); }
|
||||||
}
|
}
|
||||||
|
|
||||||
private void HS1_REV_CheckedChanged(object sender, EventArgs e)
|
private void HS1_REV_CheckedChanged(object sender, EventArgs e)
|
||||||
|
@ -1168,7 +1191,7 @@ namespace ArdupilotMega.Setup
|
||||||
{
|
{
|
||||||
MainV2.comPort.setParam(((TextBox)sender).Name, test);
|
MainV2.comPort.setParam(((TextBox)sender).Name, test);
|
||||||
}
|
}
|
||||||
catch { MessageBox.Show("Failed to set Gyro Gain"); }
|
catch { CustomMessageBox.Show("Failed to set Gyro Gain"); }
|
||||||
}
|
}
|
||||||
|
|
||||||
private void GYR_ENABLE__CheckedChanged(object sender, EventArgs e)
|
private void GYR_ENABLE__CheckedChanged(object sender, EventArgs e)
|
||||||
|
@ -1193,7 +1216,7 @@ namespace ArdupilotMega.Setup
|
||||||
}
|
}
|
||||||
catch
|
catch
|
||||||
{
|
{
|
||||||
MessageBox.Show("Failed to level : ac2 2.0.37+ is required");
|
CustomMessageBox.Show("Failed to level : ac2 2.0.37+ is required");
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -1204,7 +1227,7 @@ namespace ArdupilotMega.Setup
|
||||||
//System.Diagnostics.Process.Start("http://www.ngdc.noaa.gov/geomagmodels/Declination.jsp");
|
//System.Diagnostics.Process.Start("http://www.ngdc.noaa.gov/geomagmodels/Declination.jsp");
|
||||||
System.Diagnostics.Process.Start("http://www.magnetic-declination.com/");
|
System.Diagnostics.Process.Start("http://www.magnetic-declination.com/");
|
||||||
}
|
}
|
||||||
catch { MessageBox.Show("Webpage open failed... do you have a virus?\nhttp://www.magnetic-declination.com/"); }
|
catch { CustomMessageBox.Show("Webpage open failed... do you have a virus?\nhttp://www.magnetic-declination.com/"); }
|
||||||
}
|
}
|
||||||
|
|
||||||
void reverseChannel(string name, bool normalreverse, Control progressbar)
|
void reverseChannel(string name, bool normalreverse, Control progressbar)
|
||||||
|
@ -1229,16 +1252,16 @@ namespace ArdupilotMega.Setup
|
||||||
try
|
try
|
||||||
{
|
{
|
||||||
MainV2.comPort.setParam("SWITCH_ENABLE", 0);
|
MainV2.comPort.setParam("SWITCH_ENABLE", 0);
|
||||||
MessageBox.Show("Disabled Dip Switchs");
|
CustomMessageBox.Show("Disabled Dip Switchs");
|
||||||
}
|
}
|
||||||
catch { MessageBox.Show("Error Disableing Dip Switch"); }
|
catch { CustomMessageBox.Show("Error Disableing Dip Switch"); }
|
||||||
}
|
}
|
||||||
try
|
try
|
||||||
{
|
{
|
||||||
int i = normalreverse == false ? 1 : -1;
|
int i = normalreverse == false ? 1 : -1;
|
||||||
MainV2.comPort.setParam(name, i);
|
MainV2.comPort.setParam(name, i);
|
||||||
}
|
}
|
||||||
catch { MessageBox.Show("Error Reversing"); }
|
catch { CustomMessageBox.Show("Error Reversing"); }
|
||||||
}
|
}
|
||||||
|
|
||||||
private void CHK_revch1_CheckedChanged(object sender, EventArgs e)
|
private void CHK_revch1_CheckedChanged(object sender, EventArgs e)
|
||||||
|
@ -1267,30 +1290,30 @@ namespace ArdupilotMega.Setup
|
||||||
{
|
{
|
||||||
if (MainV2.comPort.param["HSV_MAN"].ToString() == "1")
|
if (MainV2.comPort.param["HSV_MAN"].ToString() == "1")
|
||||||
{
|
{
|
||||||
MainV2.comPort.setParam("COL_MIN_", int.Parse(COL_MIN_.Text));
|
MainV2.comPort.setParam("COL_MIN_", int.Parse(COL_MIN.Text));
|
||||||
MainV2.comPort.setParam("COL_MAX_", int.Parse(COL_MAX_.Text));
|
MainV2.comPort.setParam("COL_MAX_", int.Parse(COL_MAX.Text));
|
||||||
MainV2.comPort.setParam("HSV_MAN", 0); // randy request - last
|
MainV2.comPort.setParam("HSV_MAN", 0); // randy request - last
|
||||||
BUT_swash_manual.Text = "Manual";
|
BUT_swash_manual.Text = "Manual";
|
||||||
|
|
||||||
COL_MAX_.Enabled = false;
|
COL_MAX.Enabled = false;
|
||||||
COL_MID_.Enabled = false;
|
COL_MID.Enabled = false;
|
||||||
COL_MIN_.Enabled = false;
|
COL_MIN.Enabled = false;
|
||||||
BUT_0collective.Enabled = false;
|
BUT_0collective.Enabled = false;
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
COL_MAX_.Text = "1500";
|
COL_MAX.Text = "1500";
|
||||||
COL_MIN_.Text = "1500";
|
COL_MIN.Text = "1500";
|
||||||
MainV2.comPort.setParam("HSV_MAN", 1); // randy request
|
MainV2.comPort.setParam("HSV_MAN", 1); // randy request
|
||||||
BUT_swash_manual.Text = "Save";
|
BUT_swash_manual.Text = "Save";
|
||||||
|
|
||||||
COL_MAX_.Enabled = true;
|
COL_MAX.Enabled = true;
|
||||||
COL_MID_.Enabled = true;
|
COL_MID.Enabled = true;
|
||||||
COL_MIN_.Enabled = true;
|
COL_MIN.Enabled = true;
|
||||||
BUT_0collective.Enabled = true;
|
BUT_0collective.Enabled = true;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
catch { MessageBox.Show("Failed to set HSV_MAN"); }
|
catch { CustomMessageBox.Show("Failed to set HSV_MAN"); }
|
||||||
}
|
}
|
||||||
|
|
||||||
private void BUT_HS4save_Click(object sender, EventArgs e)
|
private void BUT_HS4save_Click(object sender, EventArgs e)
|
||||||
|
@ -1319,7 +1342,7 @@ namespace ArdupilotMega.Setup
|
||||||
HS4_MIN.Enabled = true;
|
HS4_MIN.Enabled = true;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
catch { MessageBox.Show("Failed to set HSV_MAN"); }
|
catch { CustomMessageBox.Show("Failed to set HSV_MAN"); }
|
||||||
}
|
}
|
||||||
|
|
||||||
private void tabHeli_Click(object sender, EventArgs e)
|
private void tabHeli_Click(object sender, EventArgs e)
|
||||||
|
@ -1343,10 +1366,10 @@ namespace ArdupilotMega.Setup
|
||||||
{
|
{
|
||||||
try
|
try
|
||||||
{
|
{
|
||||||
if (int.Parse(COL_MIN_.Text) > HS3.minline)
|
if (int.Parse(COL_MIN.Text) > HS3.minline)
|
||||||
COL_MIN_.Text = HS3.minline.ToString();
|
COL_MIN.Text = HS3.minline.ToString();
|
||||||
if (int.Parse(COL_MAX_.Text) < HS3.maxline)
|
if (int.Parse(COL_MAX.Text) < HS3.maxline)
|
||||||
COL_MAX_.Text = HS3.maxline.ToString();
|
COL_MAX.Text = HS3.maxline.ToString();
|
||||||
}
|
}
|
||||||
catch { }
|
catch { }
|
||||||
}
|
}
|
||||||
|
@ -1407,6 +1430,9 @@ namespace ArdupilotMega.Setup
|
||||||
timer.Dispose();
|
timer.Dispose();
|
||||||
|
|
||||||
tabControl1.SelectedIndex = 0;
|
tabControl1.SelectedIndex = 0;
|
||||||
|
|
||||||
|
// mono runs validation on all controls on exit. try and skip it
|
||||||
|
startup = true;
|
||||||
}
|
}
|
||||||
|
|
||||||
private void CHK_enableoptflow_CheckedChanged(object sender, EventArgs e)
|
private void CHK_enableoptflow_CheckedChanged(object sender, EventArgs e)
|
||||||
|
@ -1418,14 +1444,14 @@ namespace ArdupilotMega.Setup
|
||||||
{
|
{
|
||||||
if (MainV2.comPort.param["FLOW_ENABLE"] == null)
|
if (MainV2.comPort.param["FLOW_ENABLE"] == null)
|
||||||
{
|
{
|
||||||
MessageBox.Show("Not Available on " + MainV2.cs.firmware.ToString());
|
CustomMessageBox.Show("Not Available on " + MainV2.cs.firmware.ToString());
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
MainV2.comPort.setParam("FLOW_ENABLE", ((CheckBox)sender).Checked == true ? 1 : 0);
|
MainV2.comPort.setParam("FLOW_ENABLE", ((CheckBox)sender).Checked == true ? 1 : 0);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
catch { MessageBox.Show("Set FLOW_ENABLE Failed"); }
|
catch { CustomMessageBox.Show("Set FLOW_ENABLE Failed"); }
|
||||||
}
|
}
|
||||||
|
|
||||||
private void CMB_sonartype_SelectedIndexChanged(object sender, EventArgs e)
|
private void CMB_sonartype_SelectedIndexChanged(object sender, EventArgs e)
|
||||||
|
@ -1436,14 +1462,14 @@ namespace ArdupilotMega.Setup
|
||||||
{
|
{
|
||||||
if (MainV2.comPort.param["SONAR_TYPE"] == null)
|
if (MainV2.comPort.param["SONAR_TYPE"] == null)
|
||||||
{
|
{
|
||||||
MessageBox.Show("Not Available on " + MainV2.cs.firmware.ToString());
|
CustomMessageBox.Show("Not Available on " + MainV2.cs.firmware.ToString());
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
MainV2.comPort.setParam("SONAR_TYPE", ((ComboBox)sender).SelectedIndex);
|
MainV2.comPort.setParam("SONAR_TYPE", ((ComboBox)sender).SelectedIndex);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
catch { MessageBox.Show("Set SONAR_TYPE Failed"); }
|
catch { CustomMessageBox.Show("Set SONAR_TYPE Failed"); }
|
||||||
}
|
}
|
||||||
|
|
||||||
private void CHK_mixmode_CheckedChanged(object sender, EventArgs e)
|
private void CHK_mixmode_CheckedChanged(object sender, EventArgs e)
|
||||||
|
@ -1454,14 +1480,14 @@ namespace ArdupilotMega.Setup
|
||||||
{
|
{
|
||||||
if (MainV2.comPort.param["ELEVON_MIXING"] == null)
|
if (MainV2.comPort.param["ELEVON_MIXING"] == null)
|
||||||
{
|
{
|
||||||
MessageBox.Show("Not Available on " + MainV2.cs.firmware.ToString());
|
CustomMessageBox.Show("Not Available on " + MainV2.cs.firmware.ToString());
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
MainV2.comPort.setParam("ELEVON_MIXING", ((CheckBox)sender).Checked == true ? 1 : 0);
|
MainV2.comPort.setParam("ELEVON_MIXING", ((CheckBox)sender).Checked == true ? 1 : 0);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
catch { MessageBox.Show("Set ELEVON_MIXING Failed"); }
|
catch { CustomMessageBox.Show("Set ELEVON_MIXING Failed"); }
|
||||||
}
|
}
|
||||||
|
|
||||||
private void CHK_elevonrev_CheckedChanged(object sender, EventArgs e)
|
private void CHK_elevonrev_CheckedChanged(object sender, EventArgs e)
|
||||||
|
@ -1472,14 +1498,14 @@ namespace ArdupilotMega.Setup
|
||||||
{
|
{
|
||||||
if (MainV2.comPort.param["ELEVON_REVERSE"] == null)
|
if (MainV2.comPort.param["ELEVON_REVERSE"] == null)
|
||||||
{
|
{
|
||||||
MessageBox.Show("Not Available on " + MainV2.cs.firmware.ToString());
|
CustomMessageBox.Show("Not Available on " + MainV2.cs.firmware.ToString());
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
MainV2.comPort.setParam("ELEVON_REVERSE", ((CheckBox)sender).Checked == true ? 1 : 0);
|
MainV2.comPort.setParam("ELEVON_REVERSE", ((CheckBox)sender).Checked == true ? 1 : 0);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
catch { MessageBox.Show("Set ELEVON_REVERSE Failed"); }
|
catch { CustomMessageBox.Show("Set ELEVON_REVERSE Failed"); }
|
||||||
}
|
}
|
||||||
|
|
||||||
private void CHK_elevonch1rev_CheckedChanged(object sender, EventArgs e)
|
private void CHK_elevonch1rev_CheckedChanged(object sender, EventArgs e)
|
||||||
|
@ -1490,14 +1516,14 @@ namespace ArdupilotMega.Setup
|
||||||
{
|
{
|
||||||
if (MainV2.comPort.param["ELEVON_CH1_REV"] == null)
|
if (MainV2.comPort.param["ELEVON_CH1_REV"] == null)
|
||||||
{
|
{
|
||||||
MessageBox.Show("Not Available on " + MainV2.cs.firmware.ToString());
|
CustomMessageBox.Show("Not Available on " + MainV2.cs.firmware.ToString());
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
MainV2.comPort.setParam("ELEVON_CH1_REV", ((CheckBox)sender).Checked == true ? 1 : 0);
|
MainV2.comPort.setParam("ELEVON_CH1_REV", ((CheckBox)sender).Checked == true ? 1 : 0);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
catch { MessageBox.Show("Set ELEVON_CH1_REV Failed"); }
|
catch { CustomMessageBox.Show("Set ELEVON_CH1_REV Failed"); }
|
||||||
}
|
}
|
||||||
|
|
||||||
private void CHK_elevonch2rev_CheckedChanged(object sender, EventArgs e)
|
private void CHK_elevonch2rev_CheckedChanged(object sender, EventArgs e)
|
||||||
|
@ -1508,14 +1534,14 @@ namespace ArdupilotMega.Setup
|
||||||
{
|
{
|
||||||
if (MainV2.comPort.param["ELEVON_CH2_REV"] == null)
|
if (MainV2.comPort.param["ELEVON_CH2_REV"] == null)
|
||||||
{
|
{
|
||||||
MessageBox.Show("Not Available on " + MainV2.cs.firmware.ToString());
|
CustomMessageBox.Show("Not Available on " + MainV2.cs.firmware.ToString());
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
MainV2.comPort.setParam("ELEVON_CH2_REV", ((CheckBox)sender).Checked == true ? 1 : 0);
|
MainV2.comPort.setParam("ELEVON_CH2_REV", ((CheckBox)sender).Checked == true ? 1 : 0);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
catch { MessageBox.Show("Set ELEVON_CH2_REV Failed"); }
|
catch { CustomMessageBox.Show("Set ELEVON_CH2_REV Failed"); }
|
||||||
}
|
}
|
||||||
|
|
||||||
private void CMB_batmonsensortype_SelectedIndexChanged(object sender, EventArgs e)
|
private void CMB_batmonsensortype_SelectedIndexChanged(object sender, EventArgs e)
|
||||||
|
@ -1590,5 +1616,75 @@ namespace ArdupilotMega.Setup
|
||||||
TXT_inputvoltage.Enabled = true;
|
TXT_inputvoltage.Enabled = true;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
private void H1_ENABLE_CheckedChanged(object sender, EventArgs e)
|
||||||
|
{
|
||||||
|
if (startup)
|
||||||
|
return;
|
||||||
|
try
|
||||||
|
{
|
||||||
|
if (MainV2.comPort.param["H1_ENABLE"] == null)
|
||||||
|
{
|
||||||
|
CustomMessageBox.Show("Not Available on " + MainV2.cs.firmware.ToString());
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
MainV2.comPort.setParam("H1_ENABLE", ((RadioButton)sender).Checked == true ? 1 : 0);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
catch { CustomMessageBox.Show("Set H1_ENABLE Failed"); }
|
||||||
|
}
|
||||||
|
|
||||||
|
private void BUT_MagCalibration_Click(object sender, EventArgs e)
|
||||||
|
{
|
||||||
|
if (DialogResult.Yes == CustomMessageBox.Show("Use live data, or a log\n\nYes for Live data", "Mag Calibration", MessageBoxButtons.YesNo))
|
||||||
|
{
|
||||||
|
List<Tuple<float, float, float>> data = new List<Tuple<float, float, float>>();
|
||||||
|
|
||||||
|
byte backupratesens = MainV2.cs.ratesensors;
|
||||||
|
|
||||||
|
MainV2.cs.ratesensors = 10;
|
||||||
|
|
||||||
|
MainV2.comPort.requestDatastream((byte)MAVLink.MAV_DATA_STREAM.MAV_DATA_STREAM_RAW_SENSORS, MainV2.cs.ratesensors); // mag captures at 10 hz
|
||||||
|
|
||||||
|
CustomMessageBox.Show("Data will be collected for 30 seconds, Please click ok and move the apm around all axises");
|
||||||
|
|
||||||
|
DateTime deadline = DateTime.Now.AddSeconds(30);
|
||||||
|
|
||||||
|
float oldmx = 0;
|
||||||
|
float oldmy = 0;
|
||||||
|
float oldmz = 0;
|
||||||
|
|
||||||
|
while (deadline > DateTime.Now)
|
||||||
|
{
|
||||||
|
Application.DoEvents();
|
||||||
|
|
||||||
|
if (oldmx != MainV2.cs.mx &&
|
||||||
|
oldmy != MainV2.cs.my &&
|
||||||
|
oldmz != MainV2.cs.mz)
|
||||||
|
{
|
||||||
|
data.Add(new Tuple<float, float, float>(
|
||||||
|
MainV2.cs.mx - (float)MainV2.cs.mag_ofs_x,
|
||||||
|
MainV2.cs.my - (float)MainV2.cs.mag_ofs_y,
|
||||||
|
MainV2.cs.mz - (float)MainV2.cs.mag_ofs_z));
|
||||||
|
|
||||||
|
oldmx = MainV2.cs.mx;
|
||||||
|
oldmy = MainV2.cs.my;
|
||||||
|
oldmz = MainV2.cs.mz;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
MainV2.cs.ratesensors = backupratesens;
|
||||||
|
|
||||||
|
double[] ans = MagCalib.LeastSq(data);
|
||||||
|
|
||||||
|
MagCalib.SaveOffsets(ans);
|
||||||
|
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
MagCalib.ProcessLog();
|
||||||
|
}
|
||||||
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
File diff suppressed because it is too large
Load Diff
|
@ -3,11 +3,14 @@ using System.Collections.Generic;
|
||||||
using System.Linq;
|
using System.Linq;
|
||||||
using System.Text;
|
using System.Text;
|
||||||
using System.Speech.Synthesis;
|
using System.Speech.Synthesis;
|
||||||
|
using log4net;
|
||||||
|
|
||||||
namespace ArdupilotMega
|
namespace ArdupilotMega
|
||||||
{
|
{
|
||||||
public class Speech
|
public class Speech
|
||||||
{
|
{
|
||||||
|
private static readonly ILog log = LogManager.GetLogger(System.Reflection.MethodBase.GetCurrentMethod().DeclaringType);
|
||||||
|
|
||||||
SpeechSynthesizer _speechwindows;
|
SpeechSynthesizer _speechwindows;
|
||||||
System.Diagnostics.Process _speechlinux;
|
System.Diagnostics.Process _speechlinux;
|
||||||
|
|
||||||
|
@ -15,8 +18,10 @@ namespace ArdupilotMega
|
||||||
|
|
||||||
bool MONO = false;
|
bool MONO = false;
|
||||||
|
|
||||||
public SynthesizerState State {
|
public SynthesizerState State
|
||||||
get {
|
{
|
||||||
|
get
|
||||||
|
{
|
||||||
if (MONO)
|
if (MONO)
|
||||||
{
|
{
|
||||||
return _state;
|
return _state;
|
||||||
|
@ -33,6 +38,8 @@ namespace ArdupilotMega
|
||||||
var t = Type.GetType("Mono.Runtime");
|
var t = Type.GetType("Mono.Runtime");
|
||||||
MONO = (t != null);
|
MONO = (t != null);
|
||||||
|
|
||||||
|
log.Info("TTS: init, mono = " + MONO);
|
||||||
|
|
||||||
if (MONO)
|
if (MONO)
|
||||||
{
|
{
|
||||||
_state = SynthesizerState.Ready;
|
_state = SynthesizerState.Ready;
|
||||||
|
@ -47,23 +54,39 @@ namespace ArdupilotMega
|
||||||
{
|
{
|
||||||
if (MONO)
|
if (MONO)
|
||||||
{
|
{
|
||||||
if (_speechlinux == null || _speechlinux.HasExited)
|
//if (_speechlinux == null)
|
||||||
{
|
{
|
||||||
_state = SynthesizerState.Speaking;
|
_state = SynthesizerState.Speaking;
|
||||||
_speechlinux = new System.Diagnostics.Process();
|
_speechlinux = new System.Diagnostics.Process();
|
||||||
_speechlinux.StartInfo.FileName = "echo " + text + " | festival --tts";
|
_speechlinux.StartInfo.RedirectStandardInput = true;
|
||||||
|
_speechlinux.StartInfo.UseShellExecute = false;
|
||||||
|
_speechlinux.StartInfo.FileName = "festival";
|
||||||
_speechlinux.Start();
|
_speechlinux.Start();
|
||||||
_speechlinux.Exited += new EventHandler(_speechlinux_Exited);
|
_speechlinux.Exited += new EventHandler(_speechlinux_Exited);
|
||||||
|
|
||||||
|
log.Info("TTS: start " + _speechlinux.StartTime);
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
_state = SynthesizerState.Speaking;
|
||||||
|
_speechlinux.StandardInput.WriteLine("(SayText \"" + text + "\")");
|
||||||
|
_speechlinux.StandardInput.WriteLine("(quit)");
|
||||||
|
|
||||||
|
_speechlinux.Close();
|
||||||
|
|
||||||
|
_state = SynthesizerState.Ready;
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
_speechwindows.SpeakAsync(text);
|
_speechwindows.SpeakAsync(text);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
log.Info("TTS: say " + text);
|
||||||
}
|
}
|
||||||
|
|
||||||
void _speechlinux_Exited(object sender, EventArgs e)
|
void _speechlinux_Exited(object sender, EventArgs e)
|
||||||
{
|
{
|
||||||
|
log.Info("TTS: exit " + _speechlinux.ExitTime);
|
||||||
_state = SynthesizerState.Ready;
|
_state = SynthesizerState.Ready;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -0,0 +1,235 @@
|
||||||
|
using System;
|
||||||
|
using System.Drawing;
|
||||||
|
using System.Windows.Forms;
|
||||||
|
using log4net;
|
||||||
|
|
||||||
|
namespace ArdupilotMega
|
||||||
|
{
|
||||||
|
/// <summary>
|
||||||
|
/// Helper class for the stylng 'theming' of forms and controls, and provides MessageBox
|
||||||
|
/// replacements which are also styled
|
||||||
|
/// </summary>
|
||||||
|
public class ThemeManager
|
||||||
|
{
|
||||||
|
private static readonly ILog log =
|
||||||
|
LogManager.GetLogger(System.Reflection.MethodBase.GetCurrentMethod().DeclaringType);
|
||||||
|
|
||||||
|
private static Themes _currentTheme = Themes.BurntKermit;
|
||||||
|
|
||||||
|
public enum Themes
|
||||||
|
{
|
||||||
|
/// <summary>
|
||||||
|
/// no theme - standard Winforms appearance
|
||||||
|
/// </summary>
|
||||||
|
None,
|
||||||
|
|
||||||
|
/// <summary>
|
||||||
|
/// Standard Planner Charcoal & Green colours
|
||||||
|
/// </summary>
|
||||||
|
BurntKermit,
|
||||||
|
}
|
||||||
|
|
||||||
|
/// <summary>
|
||||||
|
/// Change the current theme. Existing controls are not affected
|
||||||
|
/// </summary>
|
||||||
|
/// <param name="theme"></param>
|
||||||
|
public static void SetTheme(Themes theme)
|
||||||
|
{
|
||||||
|
log.Debug("Theme set to " + Enum.GetName(typeof(Themes), theme));
|
||||||
|
_currentTheme = theme;
|
||||||
|
}
|
||||||
|
|
||||||
|
/// <summary>
|
||||||
|
/// Will recursively apply the current theme to 'control'
|
||||||
|
/// </summary>
|
||||||
|
/// <param name="control"></param>
|
||||||
|
public static void ApplyThemeTo(Control control)
|
||||||
|
{
|
||||||
|
switch (_currentTheme)
|
||||||
|
{
|
||||||
|
case Themes.BurntKermit: ApplyBurntKermitTheme(control, 0);
|
||||||
|
break;
|
||||||
|
|
||||||
|
// More themes go here
|
||||||
|
|
||||||
|
default:
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
private static void ApplyBurntKermitTheme(Control temp, int level)
|
||||||
|
{
|
||||||
|
Color BGColor = Color.FromArgb(0x26, 0x27, 0x28); // background
|
||||||
|
Color ControlBGColor = Color.FromArgb(0x43, 0x44, 0x45); // editable bg color
|
||||||
|
Color TextColor = Color.White;
|
||||||
|
|
||||||
|
if (level == 0)
|
||||||
|
{
|
||||||
|
temp.BackColor = BGColor;
|
||||||
|
temp.ForeColor = TextColor;// Color.FromArgb(0xe6, 0xe8, 0xea);
|
||||||
|
}
|
||||||
|
|
||||||
|
//temp.Font = new Font("Lucida Console", 8.25f);
|
||||||
|
|
||||||
|
foreach (Control ctl in temp.Controls)
|
||||||
|
{
|
||||||
|
if (ctl.GetType() == typeof(Button))
|
||||||
|
{
|
||||||
|
ctl.ForeColor = Color.Black;
|
||||||
|
}
|
||||||
|
else if (ctl.GetType() == typeof(MyButton))
|
||||||
|
{
|
||||||
|
Color PrimeColor = Color.FromArgb(0x94, 0xc1, 0x1f);
|
||||||
|
|
||||||
|
MyButton but = (MyButton)ctl;
|
||||||
|
//but.BGGradTop = Color.FromArgb(PrimeColor.R, PrimeColor.G, PrimeColor.B);
|
||||||
|
//but.BGGradBot = Color.FromArgb(255 - (int)(PrimeColor.R * 0.27), 255 - (int)(PrimeColor.G * 0.14), 255 - (int)(PrimeColor.B * 0.79));
|
||||||
|
//but.ForeColor = Color.FromArgb(0x40, 0x57, 0x04); //Color.FromArgb(255 - (int)(PrimeColor.R * 0.7), 255 - (int)(PrimeColor.G * 0.8), 255 - (int)(PrimeColor.B * 0.1));
|
||||||
|
//but.Outline = ControlBGColor;
|
||||||
|
}
|
||||||
|
else if (ctl.GetType() == typeof(TextBox))
|
||||||
|
{
|
||||||
|
ctl.BackColor = ControlBGColor;
|
||||||
|
ctl.ForeColor = TextColor;// Color.FromArgb(0xe6, 0xe8, 0xea);
|
||||||
|
TextBox txt = (TextBox)ctl;
|
||||||
|
txt.BorderStyle = BorderStyle.None;
|
||||||
|
}
|
||||||
|
else if (ctl.GetType() == typeof(DomainUpDown))
|
||||||
|
{
|
||||||
|
ctl.BackColor = ControlBGColor;
|
||||||
|
ctl.ForeColor = TextColor;// Color.FromArgb(0xe6, 0xe8, 0xea);
|
||||||
|
DomainUpDown txt = (DomainUpDown)ctl;
|
||||||
|
txt.BorderStyle = BorderStyle.None;
|
||||||
|
}
|
||||||
|
else if (ctl.GetType() == typeof(GroupBox))
|
||||||
|
{
|
||||||
|
ctl.BackColor = BGColor;
|
||||||
|
ctl.ForeColor = TextColor;// Color.FromArgb(0xe6, 0xe8, 0xea);
|
||||||
|
}
|
||||||
|
else if (ctl.GetType() == typeof(ZedGraph.ZedGraphControl))
|
||||||
|
{
|
||||||
|
var zg1 = (ZedGraph.ZedGraphControl)ctl;
|
||||||
|
zg1.GraphPane.Chart.Fill = new ZedGraph.Fill(Color.FromArgb(0x1f, 0x1f, 0x20));
|
||||||
|
zg1.GraphPane.Fill = new ZedGraph.Fill(Color.FromArgb(0x37, 0x37, 0x38));
|
||||||
|
|
||||||
|
foreach (ZedGraph.LineItem li in zg1.GraphPane.CurveList)
|
||||||
|
li.Line.Width = 4;
|
||||||
|
|
||||||
|
zg1.GraphPane.Title.FontSpec.FontColor = TextColor;
|
||||||
|
|
||||||
|
zg1.GraphPane.XAxis.MajorTic.Color = Color.White;
|
||||||
|
zg1.GraphPane.XAxis.MinorTic.Color = Color.White;
|
||||||
|
zg1.GraphPane.YAxis.MajorTic.Color = Color.White;
|
||||||
|
zg1.GraphPane.YAxis.MinorTic.Color = Color.White;
|
||||||
|
|
||||||
|
zg1.GraphPane.XAxis.MajorGrid.Color = Color.White;
|
||||||
|
zg1.GraphPane.YAxis.MajorGrid.Color = Color.White;
|
||||||
|
|
||||||
|
zg1.GraphPane.YAxis.Scale.FontSpec.FontColor = Color.White;
|
||||||
|
zg1.GraphPane.YAxis.Title.FontSpec.FontColor = Color.White;
|
||||||
|
|
||||||
|
zg1.GraphPane.XAxis.Scale.FontSpec.FontColor = Color.White;
|
||||||
|
zg1.GraphPane.XAxis.Title.FontSpec.FontColor = Color.White;
|
||||||
|
|
||||||
|
zg1.GraphPane.Legend.Fill = new ZedGraph.Fill(Color.FromArgb(0x85, 0x84, 0x83));
|
||||||
|
zg1.GraphPane.Legend.FontSpec.FontColor = TextColor;
|
||||||
|
}
|
||||||
|
else if (ctl.GetType() == typeof(BSE.Windows.Forms.Panel) || ctl.GetType() == typeof(SplitterPanel))
|
||||||
|
{
|
||||||
|
ctl.BackColor = BGColor;
|
||||||
|
ctl.ForeColor = TextColor;// Color.FromArgb(0xe6, 0xe8, 0xea);
|
||||||
|
}
|
||||||
|
else if (ctl.GetType() == typeof(Form))
|
||||||
|
{
|
||||||
|
ctl.BackColor = BGColor;
|
||||||
|
ctl.ForeColor = TextColor;// Color.FromArgb(0xe6, 0xe8, 0xea);
|
||||||
|
}
|
||||||
|
else if (ctl.GetType() == typeof(RichTextBox))
|
||||||
|
{
|
||||||
|
ctl.BackColor = ControlBGColor;
|
||||||
|
ctl.ForeColor = TextColor;
|
||||||
|
RichTextBox txtr = (RichTextBox)ctl;
|
||||||
|
txtr.BorderStyle = BorderStyle.None;
|
||||||
|
}
|
||||||
|
else if (ctl.GetType() == typeof(CheckedListBox))
|
||||||
|
{
|
||||||
|
ctl.BackColor = ControlBGColor;
|
||||||
|
ctl.ForeColor = TextColor;
|
||||||
|
CheckedListBox txtr = (CheckedListBox)ctl;
|
||||||
|
txtr.BorderStyle = BorderStyle.None;
|
||||||
|
}
|
||||||
|
else if (ctl.GetType() == typeof(TabPage))
|
||||||
|
{
|
||||||
|
ctl.BackColor = BGColor; //ControlBGColor
|
||||||
|
ctl.ForeColor = TextColor;
|
||||||
|
TabPage txtr = (TabPage)ctl;
|
||||||
|
txtr.BorderStyle = BorderStyle.None;
|
||||||
|
}
|
||||||
|
else if (ctl.GetType() == typeof(TabControl))
|
||||||
|
{
|
||||||
|
ctl.BackColor = BGColor; //ControlBGColor
|
||||||
|
ctl.ForeColor = TextColor;
|
||||||
|
TabControl txtr = (TabControl)ctl;
|
||||||
|
|
||||||
|
}
|
||||||
|
else if (ctl.GetType() == typeof(DataGridView))
|
||||||
|
{
|
||||||
|
ctl.ForeColor = TextColor;
|
||||||
|
DataGridView dgv = (DataGridView)ctl;
|
||||||
|
dgv.EnableHeadersVisualStyles = false;
|
||||||
|
dgv.BorderStyle = BorderStyle.None;
|
||||||
|
dgv.BackgroundColor = BGColor;
|
||||||
|
DataGridViewCellStyle rs = new DataGridViewCellStyle();
|
||||||
|
rs.BackColor = ControlBGColor;
|
||||||
|
rs.ForeColor = TextColor;
|
||||||
|
dgv.RowsDefaultCellStyle = rs;
|
||||||
|
|
||||||
|
DataGridViewCellStyle hs = new DataGridViewCellStyle(dgv.ColumnHeadersDefaultCellStyle);
|
||||||
|
hs.BackColor = BGColor;
|
||||||
|
hs.ForeColor = TextColor;
|
||||||
|
|
||||||
|
dgv.ColumnHeadersDefaultCellStyle = hs;
|
||||||
|
dgv.RowHeadersDefaultCellStyle = hs;
|
||||||
|
}
|
||||||
|
else if (ctl.GetType() == typeof(ComboBox))
|
||||||
|
{
|
||||||
|
ctl.BackColor = ControlBGColor;
|
||||||
|
ctl.ForeColor = TextColor;
|
||||||
|
ComboBox CMB = (ComboBox)ctl;
|
||||||
|
CMB.FlatStyle = FlatStyle.Flat;
|
||||||
|
}
|
||||||
|
else if (ctl.GetType() == typeof(NumericUpDown))
|
||||||
|
{
|
||||||
|
ctl.BackColor = ControlBGColor;
|
||||||
|
ctl.ForeColor = TextColor;
|
||||||
|
}
|
||||||
|
else if (ctl.GetType() == typeof(TrackBar))
|
||||||
|
{
|
||||||
|
ctl.BackColor = BGColor;
|
||||||
|
ctl.ForeColor = TextColor;
|
||||||
|
}
|
||||||
|
else if (ctl.GetType() == typeof(LinkLabel))
|
||||||
|
{
|
||||||
|
ctl.BackColor = BGColor;
|
||||||
|
ctl.ForeColor = TextColor;
|
||||||
|
LinkLabel LNK = (LinkLabel)ctl;
|
||||||
|
LNK.ActiveLinkColor = TextColor;
|
||||||
|
LNK.LinkColor = TextColor;
|
||||||
|
LNK.VisitedLinkColor = TextColor;
|
||||||
|
|
||||||
|
}
|
||||||
|
else if (ctl.GetType() == typeof(HorizontalProgressBar2) || ctl.GetType() == typeof(VerticalProgressBar2))
|
||||||
|
{
|
||||||
|
((HorizontalProgressBar2)ctl).BackgroundColor = ControlBGColor;
|
||||||
|
((HorizontalProgressBar2)ctl).ValueColor = Color.FromArgb(148, 193, 31);
|
||||||
|
}
|
||||||
|
|
||||||
|
if (ctl.Controls.Count > 0)
|
||||||
|
ApplyBurntKermitTheme(ctl, 1);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
}
|
|
@ -26,16 +26,18 @@ namespace Updater
|
||||||
|
|
||||||
string path = Path.GetDirectoryName(Application.ExecutablePath);
|
string path = Path.GetDirectoryName(Application.ExecutablePath);
|
||||||
|
|
||||||
UpdateFiles(path);
|
// give 4 seconds grace
|
||||||
|
System.Threading.Thread.Sleep(5000);
|
||||||
|
|
||||||
//if (!UpdateFiles(path))
|
//UpdateFiles(path);
|
||||||
|
|
||||||
|
if (!UpdateFiles(path))
|
||||||
{
|
{
|
||||||
// this fails on mac
|
Console.WriteLine("Update failed, please try it later.");
|
||||||
//Console.WriteLine("Update failed, please try it later.");
|
Console.WriteLine("Press any key to continue.");
|
||||||
//Console.WriteLine("Press any key to continue.");
|
Console.ReadKey();
|
||||||
//Console.ReadKey();
|
|
||||||
}
|
}
|
||||||
//else
|
else
|
||||||
{
|
{
|
||||||
try
|
try
|
||||||
{
|
{
|
||||||
|
|
|
@ -1,64 +0,0 @@
|
||||||
//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);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
|
@ -19,7 +19,7 @@
|
||||||
<appender name="RollingFile" type="log4net.Appender.RollingFileAppender">
|
<appender name="RollingFile" type="log4net.Appender.RollingFileAppender">
|
||||||
<file value="ArdupilotPlanner.log" />
|
<file value="ArdupilotPlanner.log" />
|
||||||
<appendToFile value="true" />
|
<appendToFile value="true" />
|
||||||
<maximumFileSize value="100KB" />
|
<maximumFileSize value="500KB" />
|
||||||
<maxSizeRollBackups value="2" />
|
<maxSizeRollBackups value="2" />
|
||||||
<layout type="log4net.Layout.PatternLayout">
|
<layout type="log4net.Layout.PatternLayout">
|
||||||
<conversionPattern value="%date %5level %logger - %message (%file:%line) [%thread]%newline" />
|
<conversionPattern value="%date %5level %logger - %message (%file:%line) [%thread]%newline" />
|
||||||
|
|
|
@ -1 +1,3 @@
|
||||||
*.pdb
|
*.pdb
|
||||||
|
*.etag
|
||||||
|
*.new
|
|
@ -19,7 +19,7 @@
|
||||||
<appender name="RollingFile" type="log4net.Appender.RollingFileAppender">
|
<appender name="RollingFile" type="log4net.Appender.RollingFileAppender">
|
||||||
<file value="ArdupilotPlanner.log" />
|
<file value="ArdupilotPlanner.log" />
|
||||||
<appendToFile value="true" />
|
<appendToFile value="true" />
|
||||||
<maximumFileSize value="100KB" />
|
<maximumFileSize value="500KB" />
|
||||||
<maxSizeRollBackups value="2" />
|
<maxSizeRollBackups value="2" />
|
||||||
<layout type="log4net.Layout.PatternLayout">
|
<layout type="log4net.Layout.PatternLayout">
|
||||||
<conversionPattern value="%date %5level %logger - %message (%file:%line) [%thread]%newline" />
|
<conversionPattern value="%date %5level %logger - %message (%file:%line) [%thread]%newline" />
|
||||||
|
|
Binary file not shown.
|
@ -281,7 +281,7 @@ namespace ArdupilotMega
|
||||||
sw2.Close();
|
sw2.Close();
|
||||||
sw.Close();
|
sw.Close();
|
||||||
|
|
||||||
MessageBox.Show("Done " + matchs + " matchs");
|
CustomMessageBox.Show("Done " + matchs + " matchs");
|
||||||
}
|
}
|
||||||
|
|
||||||
private void InitializeComponent()
|
private void InitializeComponent()
|
||||||
|
|
|
@ -11,7 +11,7 @@ $dir2 = "C:/Users/hog/Desktop/DIYDrones/ardupilot-mega/libraries/GCS_MAVLink/inc
|
||||||
|
|
||||||
$fname = "MAVLinkTypes.cs";
|
$fname = "MAVLinkTypes.cs";
|
||||||
|
|
||||||
&doit();
|
#&doit();
|
||||||
|
|
||||||
<STDIN>;
|
<STDIN>;
|
||||||
|
|
||||||
|
|
|
@ -190,6 +190,7 @@ namespace ArdupilotMega
|
||||||
|
|
||||||
requestThread = new Thread(requestRunner);
|
requestThread = new Thread(requestRunner);
|
||||||
requestThread.IsBackground = true;
|
requestThread.IsBackground = true;
|
||||||
|
requestThread.Name = "SRTM request runner";
|
||||||
requestThread.Start();
|
requestThread.Start();
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
|
|
|
@ -135,7 +135,7 @@ namespace ArdupilotMega
|
||||||
|
|
||||||
ArduinoComms port = new ArduinoSTK();
|
ArduinoComms port = new ArduinoSTK();
|
||||||
|
|
||||||
if (DialogResult.Yes == MessageBox.Show("is this a 1280?", "", MessageBoxButtons.YesNo))
|
if (DialogResult.Yes == CustomMessageBox.Show("is this a 1280?", "", MessageBoxButtons.YesNo))
|
||||||
{
|
{
|
||||||
port = new ArduinoSTK();
|
port = new ArduinoSTK();
|
||||||
port.BaudRate = 57600;
|
port.BaudRate = 57600;
|
||||||
|
@ -176,23 +176,23 @@ namespace ArdupilotMega
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
MessageBox.Show("Communication Error - WPs wrote but no config");
|
CustomMessageBox.Show("Communication Error - WPs wrote but no config");
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
MessageBox.Show("Communication Error - Bad data");
|
CustomMessageBox.Show("Communication Error - Bad data");
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
MessageBox.Show("Communication Error - no connection");
|
CustomMessageBox.Show("Communication Error - no connection");
|
||||||
}
|
}
|
||||||
port.Close();
|
port.Close();
|
||||||
}
|
}
|
||||||
catch (Exception ex) { MessageBox.Show("Port in use? " + ex.ToString()); port.Close(); }
|
catch (Exception ex) { CustomMessageBox.Show("Port in use? " + ex.ToString()); port.Close(); }
|
||||||
}
|
}
|
||||||
catch (Exception) { MessageBox.Show("Error reading file"); }
|
catch (Exception) { CustomMessageBox.Show("Error reading file"); }
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -207,7 +207,7 @@ namespace ArdupilotMega
|
||||||
|
|
||||||
ArduinoComms port = new ArduinoSTK();
|
ArduinoComms port = new ArduinoSTK();
|
||||||
|
|
||||||
if (DialogResult.Yes == MessageBox.Show("is this a 1280?", "", MessageBoxButtons.YesNo))
|
if (DialogResult.Yes == CustomMessageBox.Show("is this a 1280?", "", MessageBoxButtons.YesNo))
|
||||||
{
|
{
|
||||||
port = new ArduinoSTK();
|
port = new ArduinoSTK();
|
||||||
port.BaudRate = 57600;
|
port.BaudRate = 57600;
|
||||||
|
@ -247,21 +247,21 @@ namespace ArdupilotMega
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
MessageBox.Show("Communication Error - WPs wrote but no config");
|
CustomMessageBox.Show("Communication Error - WPs wrote but no config");
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
MessageBox.Show("Communication Error - Bad data");
|
CustomMessageBox.Show("Communication Error - Bad data");
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
MessageBox.Show("Communication Error - no connection");
|
CustomMessageBox.Show("Communication Error - no connection");
|
||||||
}
|
}
|
||||||
port.Close();
|
port.Close();
|
||||||
}
|
}
|
||||||
catch (Exception ex) { MessageBox.Show("Port in use? " + ex.ToString()); port.Close(); }
|
catch (Exception ex) { CustomMessageBox.Show("Port in use? " + ex.ToString()); port.Close(); }
|
||||||
}
|
}
|
||||||
|
|
||||||
private void BUT_flashdl_Click(object sender, EventArgs e)
|
private void BUT_flashdl_Click(object sender, EventArgs e)
|
||||||
|
@ -270,7 +270,7 @@ namespace ArdupilotMega
|
||||||
|
|
||||||
ArduinoComms port = new ArduinoSTK();
|
ArduinoComms port = new ArduinoSTK();
|
||||||
|
|
||||||
if (DialogResult.Yes == MessageBox.Show("is this a 1280?", "", MessageBoxButtons.YesNo))
|
if (DialogResult.Yes == CustomMessageBox.Show("is this a 1280?", "", MessageBoxButtons.YesNo))
|
||||||
{
|
{
|
||||||
port = new ArduinoSTK();
|
port = new ArduinoSTK();
|
||||||
port.BaudRate = 57600;
|
port.BaudRate = 57600;
|
||||||
|
@ -342,11 +342,11 @@ namespace ArdupilotMega
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
MessageBox.Show("Communication Error - no connection");
|
CustomMessageBox.Show("Communication Error - no connection");
|
||||||
}
|
}
|
||||||
port.Close();
|
port.Close();
|
||||||
}
|
}
|
||||||
catch (Exception ex) { MessageBox.Show("Port in use? " + ex.ToString()); port.Close(); }
|
catch (Exception ex) { CustomMessageBox.Show("Port in use? " + ex.ToString()); port.Close(); }
|
||||||
}
|
}
|
||||||
|
|
||||||
public int swapend(int value)
|
public int swapend(int value)
|
||||||
|
@ -371,10 +371,10 @@ namespace ArdupilotMega
|
||||||
sr.Close();
|
sr.Close();
|
||||||
|
|
||||||
}
|
}
|
||||||
catch (Exception ex) { MessageBox.Show("Failed to read firmware.hex : " + ex.Message); }
|
catch (Exception ex) { CustomMessageBox.Show("Failed to read firmware.hex : " + ex.Message); }
|
||||||
ArduinoComms port = new ArduinoSTK();
|
ArduinoComms port = new ArduinoSTK();
|
||||||
|
|
||||||
if (DialogResult.Yes == MessageBox.Show("is this a 1280?", "", MessageBoxButtons.YesNo))
|
if (DialogResult.Yes == CustomMessageBox.Show("is this a 1280?", "", MessageBoxButtons.YesNo))
|
||||||
{
|
{
|
||||||
port = new ArduinoSTK();
|
port = new ArduinoSTK();
|
||||||
port.BaudRate = 57600;
|
port.BaudRate = 57600;
|
||||||
|
@ -415,14 +415,14 @@ namespace ArdupilotMega
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
|
|
||||||
MessageBox.Show("Communication Error - no connection");
|
CustomMessageBox.Show("Communication Error - no connection");
|
||||||
}
|
}
|
||||||
port.Close();
|
port.Close();
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
}
|
}
|
||||||
catch (Exception ex) { MessageBox.Show("Check port settings or Port in use? " + ex.ToString()); port.Close(); }
|
catch (Exception ex) { CustomMessageBox.Show("Check port settings or Port in use? " + ex.ToString()); port.Close(); }
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -519,7 +519,7 @@ namespace ArdupilotMega
|
||||||
{
|
{
|
||||||
ArduinoComms port = new ArduinoSTK();
|
ArduinoComms port = new ArduinoSTK();
|
||||||
|
|
||||||
if (DialogResult.Yes == MessageBox.Show("is this a 1280?", "", MessageBoxButtons.YesNo))
|
if (DialogResult.Yes == CustomMessageBox.Show("is this a 1280?", "", MessageBoxButtons.YesNo))
|
||||||
{
|
{
|
||||||
port = new ArduinoSTK();
|
port = new ArduinoSTK();
|
||||||
port.BaudRate = 57600;
|
port.BaudRate = 57600;
|
||||||
|
@ -563,16 +563,16 @@ namespace ArdupilotMega
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
MessageBox.Show("Communication Error - Bad data");
|
CustomMessageBox.Show("Communication Error - Bad data");
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
MessageBox.Show("Communication Error - no connection");
|
CustomMessageBox.Show("Communication Error - no connection");
|
||||||
}
|
}
|
||||||
port.Close();
|
port.Close();
|
||||||
}
|
}
|
||||||
catch (Exception ex) { MessageBox.Show("Port Error? " + ex.ToString()); if (port != null && port.IsOpen) { port.Close(); } }
|
catch (Exception ex) { CustomMessageBox.Show("Port Error? " + ex.ToString()); if (port != null && port.IsOpen) { port.Close(); } }
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -627,16 +627,16 @@ namespace ArdupilotMega
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
MessageBox.Show("Communication Error - Bad data");
|
CustomMessageBox.Show("Communication Error - Bad data");
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
MessageBox.Show("Communication Error - no connection");
|
CustomMessageBox.Show("Communication Error - no connection");
|
||||||
}
|
}
|
||||||
port.Close();
|
port.Close();
|
||||||
}
|
}
|
||||||
catch (Exception ex) { MessageBox.Show("Port Error? " + ex.ToString()); if (port != null && port.IsOpen) { port.Close(); } }
|
catch (Exception ex) { CustomMessageBox.Show("Port Error? " + ex.ToString()); if (port != null && port.IsOpen) { port.Close(); } }
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -691,16 +691,16 @@ namespace ArdupilotMega
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
MessageBox.Show("Communication Error - Bad data");
|
CustomMessageBox.Show("Communication Error - Bad data");
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
MessageBox.Show("Communication Error - no connection");
|
CustomMessageBox.Show("Communication Error - no connection");
|
||||||
}
|
}
|
||||||
port.Close();
|
port.Close();
|
||||||
}
|
}
|
||||||
catch (Exception ex) { MessageBox.Show("Port Error? " + ex.ToString()); if (port != null && port.IsOpen) { port.Close(); } }
|
catch (Exception ex) { CustomMessageBox.Show("Port Error? " + ex.ToString()); if (port != null && port.IsOpen) { port.Close(); } }
|
||||||
}
|
}
|
||||||
|
|
||||||
private void BUT_copyto1280_Click(object sender, EventArgs e)
|
private void BUT_copyto1280_Click(object sender, EventArgs e)
|
||||||
|
@ -751,14 +751,14 @@ namespace ArdupilotMega
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
|
|
||||||
MessageBox.Show("Communication Error - no connection");
|
CustomMessageBox.Show("Communication Error - no connection");
|
||||||
}
|
}
|
||||||
port.Close();
|
port.Close();
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
}
|
}
|
||||||
catch (Exception ex) { MessageBox.Show("Check port settings or Port in use? " + ex.ToString()); port.Close(); }
|
catch (Exception ex) { CustomMessageBox.Show("Check port settings or Port in use? " + ex.ToString()); port.Close(); }
|
||||||
}
|
}
|
||||||
|
|
||||||
private void button2_Click(object sender, EventArgs e)
|
private void button2_Click(object sender, EventArgs e)
|
||||||
|
@ -771,7 +771,7 @@ namespace ArdupilotMega
|
||||||
sr.Close();
|
sr.Close();
|
||||||
|
|
||||||
}
|
}
|
||||||
catch (Exception ex) { MessageBox.Show("Failed to read firmware.hex : " + ex.Message); }
|
catch (Exception ex) { CustomMessageBox.Show("Failed to read firmware.hex : " + ex.Message); }
|
||||||
|
|
||||||
StreamWriter sw = new StreamWriter(Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + @"firmware.bin");
|
StreamWriter sw = new StreamWriter(Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + @"firmware.bin");
|
||||||
BinaryWriter bw = new BinaryWriter(sw.BaseStream);
|
BinaryWriter bw = new BinaryWriter(sw.BaseStream);
|
||||||
|
@ -858,7 +858,7 @@ namespace ArdupilotMega
|
||||||
|
|
||||||
int removed = ((GMap.NET.CacheProviders.SQLitePureImageCache)MainMap.Manager.ImageCacheLocal).DeleteOlderThan(DateTime.Now, GMap.NET.MapType.Custom);
|
int removed = ((GMap.NET.CacheProviders.SQLitePureImageCache)MainMap.Manager.ImageCacheLocal).DeleteOlderThan(DateTime.Now, GMap.NET.MapType.Custom);
|
||||||
|
|
||||||
MessageBox.Show("Removed "+removed + " images\nshrinking file next");
|
CustomMessageBox.Show("Removed "+removed + " images\nshrinking file next");
|
||||||
|
|
||||||
GMap.NET.CacheProviders.SQLitePureImageCache.VacuumDb(MainMap.CacheLocation + @"\TileDBv3\en\Data.gmdb");
|
GMap.NET.CacheProviders.SQLitePureImageCache.VacuumDb(MainMap.CacheLocation + @"\TileDBv3\en\Data.gmdb");
|
||||||
|
|
||||||
|
@ -878,7 +878,7 @@ namespace ArdupilotMega
|
||||||
private void BUT_follow_me_Click(object sender, EventArgs e)
|
private void BUT_follow_me_Click(object sender, EventArgs e)
|
||||||
{
|
{
|
||||||
SerialInput si = new SerialInput();
|
SerialInput si = new SerialInput();
|
||||||
MainV2.fixtheme((Form)si);
|
ThemeManager.ApplyThemeTo((Form)si);
|
||||||
si.Show();
|
si.Show();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -0,0 +1 @@
|
||||||
|
|
|
@ -0,0 +1,8 @@
|
||||||
|
QGC WPL 110
|
||||||
|
0 1 0 16 0 0 0 0 -35.362938 149.165085 650.000000 1
|
||||||
|
1 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.359586 149.161398 100.000000 1
|
||||||
|
2 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.366463 149.162235 100.000000 1
|
||||||
|
3 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.366131 149.164581 100.000000 1
|
||||||
|
4 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.359272 149.163757 100.000000 1
|
||||||
|
5 0 3 177 1.000000 -1.000000 0.000000 0.000000 -1.000000 0.000000 0.000000 1
|
||||||
|
6 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.359272 149.163757 100.000000 1
|
|
@ -2,7 +2,7 @@
|
||||||
|
|
||||||
AUTOTESTDIR=$(dirname $0)
|
AUTOTESTDIR=$(dirname $0)
|
||||||
|
|
||||||
fgfs \
|
nice fgfs \
|
||||||
--native-fdm=socket,in,10,,5503,udp \
|
--native-fdm=socket,in,10,,5503,udp \
|
||||||
--fdm=external \
|
--fdm=external \
|
||||||
--aircraft=Rascal110-JSBSim \
|
--aircraft=Rascal110-JSBSim \
|
||||||
|
|
|
@ -2,7 +2,7 @@
|
||||||
|
|
||||||
AUTOTESTDIR=$(dirname $0)
|
AUTOTESTDIR=$(dirname $0)
|
||||||
|
|
||||||
fgfs \
|
nice fgfs \
|
||||||
--native-fdm=socket,in,10,,5503,udp \
|
--native-fdm=socket,in,10,,5503,udp \
|
||||||
--fdm=external \
|
--fdm=external \
|
||||||
--aircraft=arducopter \
|
--aircraft=arducopter \
|
||||||
|
|
|
@ -193,24 +193,24 @@ void APM_RC_APM1::disable_out(uint8_t ch)
|
||||||
|
|
||||||
uint16_t APM_RC_APM1::InputCh(uint8_t ch)
|
uint16_t APM_RC_APM1::InputCh(uint8_t ch)
|
||||||
{
|
{
|
||||||
uint16_t result;
|
uint16_t result;
|
||||||
|
|
||||||
if (_HIL_override[ch] != 0) {
|
if (_HIL_override[ch] != 0) {
|
||||||
return _HIL_override[ch];
|
return _HIL_override[ch];
|
||||||
}
|
}
|
||||||
|
|
||||||
// Because servo pulse variables are 16 bits and the interrupts are running values could be corrupted.
|
// we need to stop interrupts to be sure we get a correct 16 bit value
|
||||||
// We dont want to stop interrupts to read radio channels so we have to do two readings to be sure that the value is correct...
|
cli();
|
||||||
result = _PWM_RAW[ch];
|
result = _PWM_RAW[ch];
|
||||||
if (result != _PWM_RAW[ch]) {
|
sei();
|
||||||
result = _PWM_RAW[ch]; // if the results are different we make a third reading (this should be fine)
|
|
||||||
}
|
|
||||||
result >>= 1; // Because timer runs at 0.5us we need to do value/2
|
|
||||||
|
|
||||||
// Limit values to a valid range
|
// Because timer runs at 0.5us we need to do value/2
|
||||||
result = constrain(result,MIN_PULSEWIDTH,MAX_PULSEWIDTH);
|
result >>= 1;
|
||||||
_radio_status=0; // Radio channel read
|
|
||||||
return(result);
|
// Limit values to a valid range
|
||||||
|
result = constrain(result,MIN_PULSEWIDTH,MAX_PULSEWIDTH);
|
||||||
|
_radio_status = 0; // Radio channel read
|
||||||
|
return result;
|
||||||
}
|
}
|
||||||
|
|
||||||
uint8_t APM_RC_APM1::GetState(void)
|
uint8_t APM_RC_APM1::GetState(void)
|
||||||
|
|
Some files were not shown because too many files have changed in this diff Show More
Loading…
Reference in New Issue