Merge branch 'master' of https://code.google.com/p/ardupilot-mega into param-suffix

This commit is contained in:
Adam M Rivera 2012-04-24 14:11:54 -05:00
commit 9fb9231ec4
166 changed files with 8736 additions and 4474 deletions

View File

@ -89,3 +89,7 @@
// #define MOT_6 CH_4
// #define MOT_7 CH_7
// #define MOT_8 CH_8
// use this to enable the new MAVLink 1.0 protocol, instead of the
// older 0.9 protocol
// #define MAVLINK10 ENABLED

View File

@ -94,7 +94,6 @@ http://code.google.com/p/ardupilot-mega/downloads/list
#include <ModeFilter.h> // Mode Filter from Filter library
#include <AverageFilter.h> // Mode Filter from Filter library
#include <AP_Relay.h> // APM relay
#include <GCS_MAVLink.h> // MAVLink GCS definitions
#include <memcheck.h>
// Configuration
@ -102,6 +101,8 @@ http://code.google.com/p/ardupilot-mega/downloads/list
#include "config.h"
#include "config_channels.h"
#include <GCS_MAVLink.h> // MAVLink GCS definitions
// Local modules
#include "Parameters.h"
#include "GCS.h"

View File

@ -8,7 +8,6 @@
#include <FastSerial.h>
#include <AP_Common.h>
#include <GCS_MAVLink.h>
#include <GPS.h>
#include <Stream.h>
#include <stdint.h>

View File

@ -1,5 +1,7 @@
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#include "Mavlink_compat.h"
// use this to prevent recursion during sensor init
static bool in_mavlink_delay;
@ -27,10 +29,62 @@ static bool mavlink_active;
static NOINLINE void send_heartbeat(mavlink_channel_t chan)
{
#if MAVLINK10 == ENABLED
uint8_t base_mode = MAV_MODE_FLAG_CUSTOM_MODE_ENABLED;
uint8_t system_status = MAV_STATE_ACTIVE;
uint32_t custom_mode = control_mode;
// work out the base_mode. This value is not very useful
// for APM, but we calculate it as best we can so a generic
// MAVLink enabled ground station can work out something about
// what the MAV is up to. The actual bit values are highly
// ambiguous for most of the APM flight modes. In practice, you
// only get useful information from the custom_mode, which maps to
// the APM flight mode and has a well defined meaning in the
// ArduPlane documentation
base_mode = MAV_MODE_FLAG_STABILIZE_ENABLED;
switch (control_mode) {
case AUTO:
case RTL:
case LOITER:
case GUIDED:
case CIRCLE:
base_mode |= MAV_MODE_FLAG_GUIDED_ENABLED;
// note that MAV_MODE_FLAG_AUTO_ENABLED does not match what
// APM does in any mode, as that is defined as "system finds its own goal
// positions", which APM does not currently do
break;
}
// all modes except INITIALISING have some form of manual
// override if stick mixing is enabled
base_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED;
#if HIL_MODE != HIL_MODE_DISABLED
base_mode |= MAV_MODE_FLAG_HIL_ENABLED;
#endif
// we are armed if we are not initialising
if (motors.armed()) {
base_mode |= MAV_MODE_FLAG_SAFETY_ARMED;
}
// indicate we have set a custom mode
base_mode |= MAV_MODE_FLAG_CUSTOM_MODE_ENABLED;
mavlink_msg_heartbeat_send(
chan,
2 /*mavlink_system.type*/, //MAV_TYPE_QUADROTOR
MAV_TYPE_QUADROTOR,
MAV_AUTOPILOT_ARDUPILOTMEGA,
base_mode,
custom_mode,
system_status);
#else // MAVLINK10
mavlink_msg_heartbeat_send(
chan,
MAV_QUADROTOR,
MAV_AUTOPILOT_ARDUPILOTMEGA);
#endif // MAVLINK10
}
static NOINLINE void send_attitude(mavlink_channel_t chan)
@ -48,6 +102,72 @@ static NOINLINE void send_attitude(mavlink_channel_t chan)
static NOINLINE void send_extended_status1(mavlink_channel_t chan, uint16_t packet_drops)
{
#if MAVLINK10 == ENABLED
uint32_t control_sensors_present = 0;
uint32_t control_sensors_enabled;
uint32_t control_sensors_health;
// first what sensors/controllers we have
control_sensors_present |= (1<<0); // 3D gyro present
control_sensors_present |= (1<<1); // 3D accelerometer present
if (g.compass_enabled) {
control_sensors_present |= (1<<2); // compass present
}
control_sensors_present |= (1<<3); // absolute pressure sensor present
if (g_gps != NULL && g_gps->status() == GPS::GPS_OK) {
control_sensors_present |= (1<<5); // GPS present
}
control_sensors_present |= (1<<10); // 3D angular rate control
control_sensors_present |= (1<<11); // attitude stabilisation
control_sensors_present |= (1<<12); // yaw position
control_sensors_present |= (1<<13); // altitude control
control_sensors_present |= (1<<14); // X/Y position control
control_sensors_present |= (1<<15); // motor control
// now what sensors/controllers are enabled
// first the sensors
control_sensors_enabled = control_sensors_present & 0x1FF;
// now the controllers
control_sensors_enabled = control_sensors_present & 0x1FF;
control_sensors_enabled |= (1<<10); // 3D angular rate control
control_sensors_enabled |= (1<<11); // attitude stabilisation
control_sensors_enabled |= (1<<13); // altitude control
control_sensors_enabled |= (1<<15); // motor control
switch (control_mode) {
case AUTO:
case RTL:
case LOITER:
case GUIDED:
case CIRCLE:
case POSITION:
control_sensors_enabled |= (1<<12); // yaw position
control_sensors_enabled |= (1<<14); // X/Y position control
break;
}
// at the moment all sensors/controllers are assumed healthy
control_sensors_health = control_sensors_present;
uint16_t battery_remaining = 1000.0 * (float)(g.pack_capacity - current_total1)/(float)g.pack_capacity; //Mavlink scaling 100% = 1000
mavlink_msg_sys_status_send(
chan,
control_sensors_present,
control_sensors_enabled,
control_sensors_health,
0,
battery_voltage1 * 1000, // mV
0,
battery_remaining, // in %
0, // comm drops %,
0, // comm drops in pkts,
0, 0, 0, 0);
#else // MAVLINK10
uint8_t mode = MAV_MODE_UNINIT;
uint8_t nav_mode = MAV_NAV_VECTOR;
@ -89,6 +209,7 @@ static NOINLINE void send_extended_status1(mavlink_channel_t chan, uint16_t pack
battery_voltage1 * 1000,
battery_remaining,
packet_drops);
#endif // MAVLINK10
}
static void NOINLINE send_meminfo(mavlink_channel_t chan)
@ -102,12 +223,15 @@ static void NOINLINE send_location(mavlink_channel_t chan)
Matrix3f rot = ahrs.get_dcm_matrix(); // neglecting angle of attack for now
mavlink_msg_global_position_int_send(
chan,
current_loc.lat,
current_loc.lng,
current_loc.alt * 10,
g_gps->ground_speed * rot.a.x,
g_gps->ground_speed * rot.b.x,
g_gps->ground_speed * rot.c.x);
millis(),
current_loc.lat, // in 1E7 degrees
current_loc.lng, // in 1E7 degrees
g_gps->altitude*10, // millimeters above sea level
current_loc.alt * 10, // millimeters above ground
g_gps->ground_speed * rot.a.x, // X speed cm/s
g_gps->ground_speed * rot.b.x, // Y speed cm/s
g_gps->ground_speed * rot.c.x,
g_gps->ground_course); // course in 1/100 degree
}
static void NOINLINE send_nav_controller_output(mavlink_channel_t chan)
@ -141,6 +265,21 @@ static void NOINLINE send_ahrs(mavlink_channel_t chan)
#endif // HIL_MODE != HIL_MODE_ATTITUDE
#ifdef DESKTOP_BUILD
void mavlink_simstate_send(uint8_t chan,
float roll,
float pitch,
float yaw,
float xAcc,
float yAcc,
float zAcc,
float p,
float q,
float r)
{
mavlink_msg_simstate_send((mavlink_channel_t)chan,
roll, pitch, yaw, xAcc, yAcc, zAcc, p, q, r);
}
// report simulator state
static void NOINLINE send_simstate(mavlink_channel_t chan)
{
@ -162,6 +301,26 @@ static void NOINLINE send_hwstatus(mavlink_channel_t chan)
static void NOINLINE send_gps_raw(mavlink_channel_t chan)
{
#if MAVLINK10 == ENABLED
uint8_t fix = g_gps->status();
if (fix == GPS::GPS_OK) {
fix = 3;
}
mavlink_msg_gps_raw_int_send(
chan,
micros(),
fix,
g_gps->latitude, // in 1E7 degrees
g_gps->longitude, // in 1E7 degrees
g_gps->altitude * 10, // in mm
g_gps->hdop,
65535,
g_gps->ground_speed, // cm/s
g_gps->ground_course, // 1/100 degrees,
g_gps->num_sats);
#else // MAVLINK10
mavlink_msg_gps_raw_send(
chan,
micros(),
@ -173,6 +332,7 @@ static void NOINLINE send_gps_raw(mavlink_channel_t chan)
current_loc.alt / 100.0, // was 0
g_gps->ground_speed / 100.0,
g_gps->ground_course / 100.0);
#endif // MAVLINK10
}
static void NOINLINE send_servo_out(mavlink_channel_t chan)
@ -185,6 +345,8 @@ static void NOINLINE send_servo_out(mavlink_channel_t chan)
mavlink_msg_rc_channels_scaled_send(
chan,
millis(),
0, // port 0
g.rc_1.servo_out,
g.rc_2.servo_out,
g.rc_3.radio_out,
@ -200,6 +362,8 @@ static void NOINLINE send_servo_out(mavlink_channel_t chan)
if(motors.armed() && motors.auto_armed()){
mavlink_msg_rc_channels_scaled_send(
chan,
millis(),
0, // port 0
g.rc_1.servo_out,
g.rc_2.servo_out,
10000 * g.rc_3.norm_output(),
@ -212,6 +376,8 @@ static void NOINLINE send_servo_out(mavlink_channel_t chan)
}else{
mavlink_msg_rc_channels_scaled_send(
chan,
millis(),
0, // port 0
0,
0,
-10000,
@ -226,6 +392,8 @@ static void NOINLINE send_servo_out(mavlink_channel_t chan)
#else
mavlink_msg_rc_channels_scaled_send(
chan,
millis(),
0, // port 0
g.rc_1.servo_out,
g.rc_2.servo_out,
g.rc_3.radio_out,
@ -244,6 +412,8 @@ static void NOINLINE send_radio_in(mavlink_channel_t chan)
const uint8_t rssi = 1;
mavlink_msg_rc_channels_raw_send(
chan,
millis(),
0, // port
g.rc_1.radio_in,
g.rc_2.radio_in,
g.rc_3.radio_in,
@ -259,6 +429,8 @@ static void NOINLINE send_radio_out(mavlink_channel_t chan)
{
mavlink_msg_servo_output_raw_send(
chan,
micros(),
0, // port
motors.motor_out[AP_MOTORS_MOT_1],
motors.motor_out[AP_MOTORS_MOT_2],
motors.motor_out[AP_MOTORS_MOT_3],
@ -397,7 +569,11 @@ static bool mavlink_try_send_message(mavlink_channel_t chan, enum ap_message id,
break;
case MSG_GPS_RAW:
#if MAVLINK10 == ENABLED
CHECK_PAYLOAD_SIZE(GPS_RAW_INT);
#else
CHECK_PAYLOAD_SIZE(GPS_RAW);
#endif
send_gps_raw(chan);
break;
@ -576,7 +752,7 @@ void mavlink_send_text(mavlink_channel_t chan, gcs_severity severity, const char
mavlink_msg_statustext_send(
chan,
severity,
(const int8_t*) str);
str);
}
}
@ -889,6 +1065,67 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
break;
}
#if MAVLINK10 == ENABLED
case MAVLINK_MSG_ID_COMMAND_LONG:
{
// decode
mavlink_command_long_t packet;
mavlink_msg_command_long_decode(msg, &packet);
if (mavlink_check_target(packet.target_system, packet.target_component)) break;
uint8_t result;
// do command
send_text(SEVERITY_LOW,PSTR("command received: "));
switch(packet.command) {
case MAV_CMD_NAV_LOITER_UNLIM:
set_mode(LOITER);
result = MAV_RESULT_ACCEPTED;
break;
case MAV_CMD_NAV_RETURN_TO_LAUNCH:
set_mode(RTL);
result = MAV_RESULT_ACCEPTED;
break;
case MAV_CMD_NAV_LAND:
set_mode(LAND);
result = MAV_RESULT_ACCEPTED;
break;
case MAV_CMD_MISSION_START:
set_mode(AUTO);
result = MAV_RESULT_ACCEPTED;
break;
case MAV_CMD_PREFLIGHT_CALIBRATION:
if (packet.param1 == 1 ||
packet.param2 == 1 ||
packet.param3 == 1) {
imu.init_accel(mavlink_delay, flash_leds);
}
if (packet.param4 == 1) {
trim_radio();
}
result = MAV_RESULT_ACCEPTED;
break;
default:
result = MAV_RESULT_UNSUPPORTED;
break;
}
mavlink_msg_command_ack_send(
chan,
packet.command,
result);
break;
}
#else // !MAVLINK10
case MAVLINK_MSG_ID_ACTION: //10
{
// decode
@ -1021,6 +1258,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
break;
}
#endif // MAVLINK10
case MAVLINK_MSG_ID_SET_MODE: //11
{
@ -1028,7 +1266,32 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
mavlink_set_mode_t packet;
mavlink_msg_set_mode_decode(msg, &packet);
switch(packet.mode){
#if MAVLINK10 == ENABLED
if (!(packet.base_mode & MAV_MODE_FLAG_CUSTOM_MODE_ENABLED)) {
// we ignore base_mode as there is no sane way to map
// from that bitmap to a APM flight mode. We rely on
// custom_mode instead.
break;
}
switch (packet.custom_mode) {
case STABILIZE:
case ACRO:
case ALT_HOLD:
case AUTO:
case GUIDED:
case LOITER:
case RTL:
case CIRCLE:
case POSITION:
case LAND:
case OF_LOITER:
case APPROACH:
set_mode(packet.custom_mode);
break;
}
#else // MAVLINK10
switch (packet.mode) {
case MAV_MODE_MANUAL:
set_mode(STABILIZE);
@ -1049,6 +1312,8 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
set_mode(STABILIZE);
break;
}
#endif // MAVLINK10
break;
}
/*case MAVLINK_MSG_ID_SET_NAV_MODE:
@ -1541,8 +1806,9 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
// a fractional value to an integer type
mavlink_msg_param_value_send(
chan,
(int8_t *)key,
key,
vp->cast_to_float(var_type),
mav_var_type(var_type),
_count_parameters(),
-1); // XXX we don't actually know what its index is...
@ -1780,8 +2046,9 @@ GCS_MAVLINK::queued_param_send()
mavlink_msg_param_value_send(
chan,
(int8_t*)param_name,
param_name,
value,
mav_var_type(_queued_parameter_type),
_queued_parameter_count,
_queued_parameter_index);
@ -1920,3 +2187,19 @@ static void gcs_send_text_fmt(const prog_char_t *fmt, ...)
mavlink_send_message(MAVLINK_COMM_1, MSG_STATUSTEXT, 0);
}
}
// this code was moved from libraries/GCS_MAVLink to allow compile
// time selection of MAVLink 1.0
BetterStream *mavlink_comm_0_port;
BetterStream *mavlink_comm_1_port;
mavlink_system_t mavlink_system = {7,1,0,0};
uint8_t mavlink_check_target(uint8_t sysid, uint8_t compid)
{
if (sysid != mavlink_system.sysid)
return 1;
// Currently we are not checking for correct compid since APM is not passing mavlink info to any subsystem
// If it is addressed to our system ID we assume it is for us
return 0; // no error
}

View File

@ -28,11 +28,14 @@ apm2beta:
make -f Makefile EXTRAFLAGS="-DCONFIG_APM_HARDWARE=APM_HARDWARE_APM2 -DAPM2_BETA_HARDWARE"
mavlink10:
make -f Makefile EXTRAFLAGS="-DMAVLINK10"
make -f Makefile EXTRAFLAGS="-DMAVLINK10=1"
sitl:
make -f ../libraries/Desktop/Makefile.desktop
sitl-mavlink10:
make -f ../libraries/Desktop/Makefile.desktop EXTRAFLAGS="-DMAVLINK10=1"
sitl-octa:
make -f ../libraries/Desktop/Makefile.desktop octa

View File

@ -224,8 +224,6 @@
#define RELAY_TOGGLE 5
#define STOP_REPEAT 10
//#define MAV_CMD_CONDITION_YAW 23
// GCS Message ID's
/// NOTE: to ensure we never block on sending MAVLink messages
/// please keep each MSG_ to a single MAVLink message. If need be

View File

@ -28,3 +28,6 @@
*/
// use this to enable the new MAVLink 1.0 protocol, instead of the
// older 0.9 protocol
// #define MAVLINK10 ENABLED

View File

@ -47,13 +47,14 @@ version 2.1 of the License, or (at your option) any later version.
#include <Filter.h> // Filter library
#include <ModeFilter.h> // Mode Filter from Filter library
#include <AP_Relay.h> // APM relay
#include <AP_Mount.h> // Camera/Antenna mount
#include <GCS_MAVLink.h> // MAVLink GCS definitions
#include <memcheck.h>
// Configuration
#include "config.h"
#include <GCS_MAVLink.h> // MAVLink GCS definitions
#include <AP_Mount.h> // Camera/Antenna mount
// Local modules
#include "defines.h"
#include "Parameters.h"

View File

@ -8,7 +8,6 @@
#include <FastSerial.h>
#include <AP_Common.h>
#include <GCS_MAVLink.h>
#include <GPS.h>
#include <Stream.h>
#include <stdint.h>

View File

@ -27,7 +27,7 @@ static bool mavlink_active;
static NOINLINE void send_heartbeat(mavlink_channel_t chan)
{
#ifdef MAVLINK10
#if MAVLINK10 == ENABLED
uint8_t base_mode = MAV_MODE_FLAG_CUSTOM_MODE_ENABLED;
uint8_t system_status = MAV_STATE_ACTIVE;
uint32_t custom_mode = control_mode;
@ -130,7 +130,7 @@ static NOINLINE void send_fence_status(mavlink_channel_t chan)
static NOINLINE void send_extended_status1(mavlink_channel_t chan, uint16_t packet_drops)
{
#ifdef MAVLINK10
#if MAVLINK10 == ENABLED
uint32_t control_sensors_present = 0;
uint32_t control_sensors_enabled;
uint32_t control_sensors_health;
@ -142,7 +142,7 @@ static NOINLINE void send_extended_status1(mavlink_channel_t chan, uint16_t pack
control_sensors_present |= (1<<2); // compass present
}
control_sensors_present |= (1<<3); // absolute pressure sensor present
if (g_gps != NULL && g_gps->fix) {
if (g_gps != NULL && g_gps->status() == GPS::GPS_OK) {
control_sensors_present |= (1<<5); // GPS present
}
control_sensors_present |= (1<<10); // 3D angular rate control
@ -337,12 +337,10 @@ static void NOINLINE send_nav_controller_output(mavlink_channel_t chan)
static void NOINLINE send_gps_raw(mavlink_channel_t chan)
{
#ifdef MAVLINK10
uint8_t fix;
if (g_gps->status() == 2) {
#if MAVLINK10 == ENABLED
uint8_t fix = g_gps->status();
if (fix == GPS::GPS_OK) {
fix = 3;
} else {
fix = 0;
}
mavlink_msg_gps_raw_int_send(
@ -418,14 +416,14 @@ static void NOINLINE send_radio_out(mavlink_channel_t chan)
chan,
micros(),
0, // port
g.channel_roll.radio_out,
g.channel_pitch.radio_out,
g.channel_throttle.radio_out,
g.channel_rudder.radio_out,
g.rc_5.radio_out, // XXX currently only 4 RC channels defined
g.rc_6.radio_out,
g.rc_7.radio_out,
g.rc_8.radio_out);
APM_RC.OutputCh_current(0),
APM_RC.OutputCh_current(1),
APM_RC.OutputCh_current(2),
APM_RC.OutputCh_current(3),
APM_RC.OutputCh_current(4),
APM_RC.OutputCh_current(5),
APM_RC.OutputCh_current(6),
APM_RC.OutputCh_current(7));
}
static void NOINLINE send_vfr_hud(mavlink_channel_t chan)
@ -503,6 +501,21 @@ static void NOINLINE send_ahrs(mavlink_channel_t chan)
#endif // HIL_MODE != HIL_MODE_ATTITUDE
#ifdef DESKTOP_BUILD
void mavlink_simstate_send(uint8_t chan,
float roll,
float pitch,
float yaw,
float xAcc,
float yAcc,
float zAcc,
float p,
float q,
float r)
{
mavlink_msg_simstate_send((mavlink_channel_t)chan,
roll, pitch, yaw, xAcc, yAcc, zAcc, p, q, r);
}
// report simulator state
static void NOINLINE send_simstate(mavlink_channel_t chan)
{
@ -594,7 +607,7 @@ static bool mavlink_try_send_message(mavlink_channel_t chan, enum ap_message id,
break;
case MSG_GPS_RAW:
#ifdef MAVLINK10
#if MAVLINK10 == ENABLED
CHECK_PAYLOAD_SIZE(GPS_RAW_INT);
#else
CHECK_PAYLOAD_SIZE(GPS_RAW);
@ -1084,7 +1097,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
break;
}
#ifdef MAVLINK10
#if MAVLINK10 == ENABLED
case MAVLINK_MSG_ID_COMMAND_LONG:
{
// decode
@ -1109,15 +1122,10 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
result = MAV_RESULT_ACCEPTED;
break;
#if 0
// not implemented yet, but could implement some of them
case MAV_CMD_NAV_LAND:
case MAV_CMD_NAV_TAKEOFF:
case MAV_CMD_NAV_ROI:
case MAV_CMD_NAV_PATHPLANNING:
case MAV_CMD_MISSION_START:
set_mode(AUTO);
result = MAV_RESULT_ACCEPTED;
break;
#endif
case MAV_CMD_PREFLIGHT_CALIBRATION:
if (packet.param1 == 1 ||
@ -1279,7 +1287,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
mavlink_set_mode_t packet;
mavlink_msg_set_mode_decode(msg, &packet);
#ifdef MAVLINK10
#if MAVLINK10 == ENABLED
if (!(packet.base_mode & MAV_MODE_FLAG_CUSTOM_MODE_ENABLED)) {
// we ignore base_mode as there is no sane way to map
// from that bitmap to a APM flight mode. We rely on
@ -1335,7 +1343,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
break;
}
#ifndef MAVLINK10
#if MAVLINK10 == DISABLED
case MAVLINK_MSG_ID_SET_NAV_MODE:
{
// decode
@ -1687,7 +1695,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
break;
default:
#ifdef MAVLINK10
#if MAVLINK10 == ENABLED
result = MAV_MISSION_UNSUPPORTED;
#endif
break;
@ -1903,7 +1911,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
#if HIL_MODE != HIL_MODE_DISABLED
// This is used both as a sensor and to pass the location
// in HIL_ATTITUDE mode.
#ifdef MAVLINK10
#if MAVLINK10 == ENABLED
case MAVLINK_MSG_ID_GPS_RAW_INT:
{
// decode
@ -1941,7 +1949,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
airspeed = 100*packet.airspeed;
break;
}
#ifdef MAVLINK10
#if MAVLINK10 == ENABLED
case MAVLINK_MSG_ID_HIL_STATE:
{
mavlink_hil_state_t packet;
@ -2264,3 +2272,19 @@ static void gcs_send_text_fmt(const prog_char_t *fmt, ...)
mavlink_send_message(MAVLINK_COMM_1, MSG_STATUSTEXT, 0);
}
}
// this code was moved from libraries/GCS_MAVLink to allow compile
// time selection of MAVLink 1.0
BetterStream *mavlink_comm_0_port;
BetterStream *mavlink_comm_1_port;
mavlink_system_t mavlink_system = {7,1,0,0};
uint8_t mavlink_check_target(uint8_t sysid, uint8_t compid)
{
if (sysid != mavlink_system.sysid)
return 1;
// Currently we are not checking for correct compid since APM is not passing mavlink info to any subsystem
// If it is addressed to our system ID we assume it is for us
return 0; // no error
}

View File

@ -25,13 +25,16 @@ apm2beta:
make -f Makefile EXTRAFLAGS="-DCONFIG_APM_HARDWARE=APM_HARDWARE_APM2 -DAPM2_BETA_HARDWARE"
mavlink10:
make -f Makefile EXTRAFLAGS="-DMAVLINK10"
make -f Makefile EXTRAFLAGS="-DMAVLINK10=1"
sitl:
make -f ../libraries/Desktop/Makefile.desktop
sitl-mavlink10:
make -f ../libraries/Desktop/Makefile.desktop EXTRAFLAGS="-DMAVLINK10"
make -f ../libraries/Desktop/Makefile.desktop EXTRAFLAGS="-DMAVLINK10=1"
sitl-mount:
make -f ../libraries/Desktop/Makefile.desktop EXTRAFLAGS="-DMOUNT=ENABLED"
sitl-quaternion:
make -f ../libraries/Desktop/Makefile.desktop EXTRAFLAGS="-DQUATERNION_ENABLE=ENABLED"

View File

@ -95,8 +95,6 @@
#define RELAY_TOGGLE 5
#define STOP_REPEAT 10
#define MAV_CMD_CONDITION_YAW 23
// GCS Message ID's
/// NOTE: to ensure we never block on sending MAVLink messages
/// please keep each MSG_ to a single MAVLink message. If need be

View File

@ -7,7 +7,7 @@ namespace ArdupilotMega.Antenna
{
class ArduTracker : ITrackerOutput
{
public SerialPort ComPort { get; set; }
public Comms.SerialPort ComPort { get; set; }
/// <summary>
/// 0-360
/// </summary>

View File

@ -7,7 +7,7 @@ namespace ArdupilotMega.Antenna
{
interface ITrackerOutput
{
SerialPort ComPort { get; set; }
Comms.SerialPort ComPort { get; set; }
double TrimPan { get; set; }
double TrimTilt { get; set; }

View File

@ -7,7 +7,7 @@ namespace ArdupilotMega.Antenna
{
class Maestro : ITrackerOutput
{
public SerialPort ComPort { get; set; }
public Comms.SerialPort ComPort { get; set; }
/// <summary>
/// 0-360
/// </summary>

View File

@ -52,7 +52,7 @@
this.label10 = new System.Windows.Forms.Label();
this.label11 = new System.Windows.Forms.Label();
this.label12 = new System.Windows.Forms.Label();
this.BUT_connect = new ArdupilotMega.MyButton();
this.BUT_connect = new ArdupilotMega.Controls.MyButton();
this.LBL_pantrim = new System.Windows.Forms.Label();
this.LBL_tilttrim = new System.Windows.Forms.Label();
((System.ComponentModel.ISupportInitialize)(this.TRK_pantrim)).BeginInit();
@ -266,7 +266,7 @@
private System.Windows.Forms.ComboBox CMB_interface;
private System.Windows.Forms.Label label1;
private System.Windows.Forms.ComboBox CMB_baudrate;
private MyButton BUT_connect;
private ArdupilotMega.Controls.MyButton BUT_connect;
private System.Windows.Forms.ComboBox CMB_serialport;
private System.Windows.Forms.TrackBar TRK_pantrim;
private System.Windows.Forms.TextBox TXT_panrange;

View File

@ -7,6 +7,7 @@ using System.Linq;
using System.Text;
using System.Windows.Forms;
using ArdupilotMega.Controls.BackstageView;
using ArdupilotMega.Comms;
namespace ArdupilotMega.Antenna
{

View File

@ -750,7 +750,7 @@
<value>BUT_connect</value>
</data>
<data name="&gt;&gt;BUT_connect.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null</value>
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;BUT_connect.Parent" xml:space="preserve">
<value>$this</value>

View File

@ -1,38 +1,38 @@
using System;
using System.Collections.Generic;
using System.Text;
using System.IO.Ports;
using System.IO;
namespace ArdupilotMega
{
public delegate void ProgressEventHandler(int progress,string status);
/// <summary>
/// Arduino STK interface
/// </summary>
interface ArduinoComms
{
bool connectAP();
bool keepalive();
bool sync();
byte[] download(short length);
byte[] downloadflash(short length);
bool setaddress(int address);
bool upload(byte[] data, short startfrom, short length, short startaddress);
bool uploadflash(byte[] data, int startfrom, int length, int startaddress);
event ProgressEventHandler Progress;
// from serialport class
int BaudRate { get; set; }
bool DtrEnable { get; set; }
string PortName { get; set; }
StopBits StopBits { get; set; }
Parity Parity { get; set; }
bool IsOpen { get; }
void Open();
void Close();
int DataBits { get; set; }
}
}
using System;
using System.Collections.Generic;
using System.Text;
using System.IO.Ports;
using System.IO;
namespace ArdupilotMega.Arduino
{
public delegate void ProgressEventHandler(int progress,string status);
/// <summary>
/// Arduino STK interface
/// </summary>
interface ArduinoComms
{
bool connectAP();
bool keepalive();
bool sync();
byte[] download(short length);
byte[] downloadflash(short length);
bool setaddress(int address);
bool upload(byte[] data, short startfrom, short length, short startaddress);
bool uploadflash(byte[] data, int startfrom, int length, int startaddress);
event ProgressEventHandler Progress;
// from serialport class
int BaudRate { get; set; }
bool DtrEnable { get; set; }
string PortName { get; set; }
StopBits StopBits { get; set; }
Parity Parity { get; set; }
bool IsOpen { get; }
void Open();
void Close();
int DataBits { get; set; }
}
}

View File

@ -1,460 +1,461 @@
using System;
using System.Reflection;
using System.Management;
using System.Windows.Forms;
using System.Threading;
using log4net;
using System.Globalization;
namespace ArdupilotMega
{
class ArduinoDetect
{
private static readonly ILog log = LogManager.GetLogger(MethodBase.GetCurrentMethod().DeclaringType);
/// <summary>
/// detects STK version 1 or 2
/// </summary>
/// <param name="port">comportname</param>
/// <returns>string either (1280/2560) or "" for none</returns>
public static string DetectVersion(string port)
{
SerialPort serialPort = new SerialPort();
serialPort.PortName = port;
if (serialPort.IsOpen)
serialPort.Close();
serialPort.DtrEnable = true;
serialPort.BaudRate = 57600;
serialPort.Open();
Thread.Sleep(100);
int a = 0;
while (a < 20) // 20 * 50 = 1 sec
{
//Console.WriteLine("write " + DateTime.Now.Millisecond);
serialPort.DiscardInBuffer();
serialPort.Write(new byte[] { (byte)'0', (byte)' ' }, 0, 2);
a++;
Thread.Sleep(50);
//Console.WriteLine("btr {0}", serialPort.BytesToRead);
if (serialPort.BytesToRead >= 2)
{
byte b1 = (byte)serialPort.ReadByte();
byte b2 = (byte)serialPort.ReadByte();
if (b1 == 0x14 && b2 == 0x10)
{
serialPort.Close();
return "1280";
}
}
}
serialPort.Close();
log.Warn("Not a 1280");
Thread.Sleep(500);
serialPort.DtrEnable = true;
serialPort.BaudRate = 115200;
serialPort.Open();
Thread.Sleep(100);
a = 0;
while (a < 4)
{
byte[] temp = new byte[] { 0x6, 0, 0, 0, 0 };
temp = ArduinoDetect.genstkv2packet(serialPort, temp);
a++;
Thread.Sleep(50);
try
{
if (temp[0] == 6 && temp[1] == 0 && temp.Length == 2)
{
serialPort.Close();
return "2560";
}
}
catch
{
}
}
serialPort.Close();
log.Warn("Not a 2560");
return "";
}
/// <summary>
/// Detects APM board version
/// </summary>
/// <param name="port"></param>
/// <returns> (1280/2560/2560-2)</returns>
public static string DetectBoard(string port)
{
SerialPort serialPort = new SerialPort();
serialPort.PortName = port;
if (serialPort.IsOpen)
serialPort.Close();
serialPort.DtrEnable = true;
serialPort.BaudRate = 57600;
serialPort.Open();
Thread.Sleep(100);
int a = 0;
while (a < 20) // 20 * 50 = 1 sec
{
//Console.WriteLine("write " + DateTime.Now.Millisecond);
serialPort.DiscardInBuffer();
serialPort.Write(new byte[] { (byte)'0', (byte)' ' }, 0, 2);
a++;
Thread.Sleep(50);
//Console.WriteLine("btr {0}", serialPort.BytesToRead);
if (serialPort.BytesToRead >= 2)
{
byte b1 = (byte)serialPort.ReadByte();
byte b2 = (byte)serialPort.ReadByte();
if (b1 == 0x14 && b2 == 0x10)
{
serialPort.Close();
return "1280";
}
}
}
serialPort.Close();
log.Warn("Not a 1280");
Thread.Sleep(500);
serialPort.DtrEnable = true;
serialPort.BaudRate = 115200;
serialPort.Open();
Thread.Sleep(100);
a = 0;
while (a < 4)
{
byte[] temp = new byte[] { 0x6, 0, 0, 0, 0 };
temp = ArduinoDetect.genstkv2packet(serialPort, temp);
a++;
Thread.Sleep(50);
try
{
if (temp[0] == 6 && temp[1] == 0 && temp.Length == 2)
{
serialPort.Close();
//HKEY_LOCAL_MACHINE\SYSTEM\CurrentControlSet\Enum\USB\VID_2341&PID_0010\640333439373519060F0\Device Parameters
if (!MainV2.MONO && !Thread.CurrentThread.CurrentUICulture.IsChildOf(CultureInfoEx.GetCultureInfo("zh-Hans")))
{
ObjectQuery query = new ObjectQuery("SELECT * FROM Win32_USBControllerDevice");
ManagementObjectSearcher searcher = new ManagementObjectSearcher(query);
foreach (ManagementObject obj2 in searcher.Get())
{
//Console.WriteLine("Dependant : " + obj2["Dependent"]);
// all apm 1-1.4 use a ftdi on the imu board.
if (obj2["Dependent"].ToString().Contains(@"USB\\VID_2341&PID_0010"))
{
return "2560-2";
}
}
return "2560";
}
else
{
if (DialogResult.Yes == CustomMessageBox.Show("Is this a APM 2?", "APM 2", MessageBoxButtons.YesNo))
{
return "2560-2";
}
else
{
return "2560";
}
}
}
}
catch { }
}
serialPort.Close();
log.Warn("Not a 2560");
return "";
}
public enum ap_var_type
{
AP_PARAM_NONE = 0,
AP_PARAM_INT8,
AP_PARAM_INT16,
AP_PARAM_INT32,
AP_PARAM_FLOAT,
AP_PARAM_VECTOR3F,
AP_PARAM_VECTOR6F,
AP_PARAM_MATRIX3F,
AP_PARAM_GROUP
};
static string[] type_names = new string[] {
"NONE", "INT8", "INT16", "INT32", "FLOAT", "VECTOR3F", "VECTOR6F","MATRIX6F", "GROUP"
};
static byte type_size(ap_var_type type)
{
switch (type) {
case ap_var_type.AP_PARAM_NONE:
case ap_var_type.AP_PARAM_GROUP:
return 0;
case ap_var_type.AP_PARAM_INT8:
return 1;
case ap_var_type.AP_PARAM_INT16:
return 2;
case ap_var_type.AP_PARAM_INT32:
return 4;
case ap_var_type.AP_PARAM_FLOAT:
return 4;
case ap_var_type.AP_PARAM_VECTOR3F:
return 3*4;
case ap_var_type.AP_PARAM_VECTOR6F:
return 6*4;
case ap_var_type.AP_PARAM_MATRIX3F:
return 3*3*4;
}
return 0;
}
/// <summary>
/// return the software id from eeprom
/// </summary>
/// <param name="comport">Port</param>
/// <param name="version">Board type</param>
/// <returns></returns>
public static int decodeApVar(string comport, string version)
{
ArduinoComms port = new ArduinoSTK();
if (version == "1280")
{
port = new ArduinoSTK();
port.BaudRate = 57600;
}
else if (version == "2560" || version == "2560-2")
{
port = new ArduinoSTKv2();
port.BaudRate = 115200;
}
else { return -1; }
port.PortName = comport;
port.DtrEnable = true;
port.Open();
port.connectAP();
byte[] buffer = port.download(1024 * 4);
port.Close();
if (buffer[0] != 'A' && buffer[0] != 'P' || buffer[1] != 'P' && buffer[1] != 'A') // this is the apvar header
{
return -1;
}
else
{
if (buffer[0] == 'A' && buffer[1] == 'P' && buffer[2] == 2)
{ // apvar header and version
int pos = 4;
byte key = 0;
while (pos < (1024 * 4))
{
int size = buffer[pos] & 63;
pos++;
key = buffer[pos];
pos++;
log.InfoFormat("{0:X4}: key {1} size {2}\n ", pos - 2, key, size + 1);
if (key == 0xff)
{
log.InfoFormat("end sentinal at {0}", pos - 2);
break;
}
if (key == 0)
{
//Array.Reverse(buffer, pos, 2);
return BitConverter.ToUInt16(buffer, pos);
}
for (int i = 0; i <= size; i++)
{
Console.Write(" {0:X2}", buffer[pos]);
pos++;
}
}
}
if (buffer[0] == 'P' && buffer[1] == 'A' && buffer[2] == 5) // ap param
{
int pos = 4;
byte key = 0;
while (pos < (1024 * 4))
{
key = buffer[pos];
pos++;
int group = buffer[pos];
pos++;
int type = buffer[pos];
pos++;
int size = type_size((ap_var_type)Enum.Parse(typeof(ap_var_type), type.ToString()));
Console.Write("{0:X4}: type {1} ({2}) key {3} group {4} size {5}\n ", pos - 2, type, type_names[type], key, group, size);
if (key == 0xff)
{
log.InfoFormat("end sentinal at {0}", pos - 2);
break;
}
if (key == 0)
{
//Array.Reverse(buffer, pos, 2);
return BitConverter.ToUInt16(buffer, pos);
}
for (int i = 0; i < size; i++)
{
Console.Write(" {0:X2}", buffer[pos]);
pos++;
}
}
}
}
return -1;
}
/// <summary>
/// STK v2 generate packet
/// </summary>
/// <param name="serialPort"></param>
/// <param name="message"></param>
/// <returns></returns>
static byte[] genstkv2packet(SerialPort serialPort, byte[] message)
{
byte[] data = new byte[300];
byte ck = 0;
data[0] = 0x1b;
ck ^= data[0];
data[1] = 0x1;
ck ^= data[1];
data[2] = (byte)((message.Length >> 8) & 0xff);
ck ^= data[2];
data[3] = (byte)(message.Length & 0xff);
ck ^= data[3];
data[4] = 0xe;
ck ^= data[4];
int a = 5;
foreach (byte let in message)
{
data[a] = let;
ck ^= let;
a++;
}
data[a] = ck;
a++;
serialPort.Write(data, 0, a);
//Console.WriteLine("about to read packet");
byte[] ret = ArduinoDetect.readpacket(serialPort);
//if (ret[1] == 0x0)
{
//Console.WriteLine("received OK");
}
return ret;
}
/// <summary>
///
/// </summary>
/// <param name="serialPort"></param>
/// <returns></returns>
static byte[] readpacket(SerialPort serialPort)
{
byte[] temp = new byte[4000];
byte[] mes = new byte[2] { 0x0, 0xC0 }; // fail
int a = 7;
int count = 0;
serialPort.ReadTimeout = 1000;
while (count < a)
{
//Console.WriteLine("count {0} a {1} mes leng {2}",count,a,mes.Length);
try
{
temp[count] = (byte)serialPort.ReadByte();
}
catch { break; }
//Console.Write("{1}", temp[0], (char)temp[0]);
if (temp[0] != 0x1b)
{
count = 0;
continue;
}
if (count == 3)
{
a = (temp[2] << 8) + temp[3];
mes = new byte[a];
a += 5;
}
if (count >= 5)
{
mes[count - 5] = temp[count];
}
count++;
}
//Console.WriteLine("read ck");
try
{
temp[count] = (byte)serialPort.ReadByte();
}
catch { }
count++;
Array.Resize<byte>(ref temp, count);
//Console.WriteLine(this.BytesToRead);
return mes;
}
}
using System;
using System.Reflection;
using System.Management;
using System.Windows.Forms;
using System.Threading;
using log4net;
using System.Globalization;
using ArdupilotMega.Comms;
namespace ArdupilotMega.Arduino
{
class ArduinoDetect
{
private static readonly ILog log = LogManager.GetLogger(MethodBase.GetCurrentMethod().DeclaringType);
/// <summary>
/// detects STK version 1 or 2
/// </summary>
/// <param name="port">comportname</param>
/// <returns>string either (1280/2560) or "" for none</returns>
public static string DetectVersion(string port)
{
SerialPort serialPort = new SerialPort();
serialPort.PortName = port;
if (serialPort.IsOpen)
serialPort.Close();
serialPort.DtrEnable = true;
serialPort.BaudRate = 57600;
serialPort.Open();
Thread.Sleep(100);
int a = 0;
while (a < 20) // 20 * 50 = 1 sec
{
//Console.WriteLine("write " + DateTime.Now.Millisecond);
serialPort.DiscardInBuffer();
serialPort.Write(new byte[] { (byte)'0', (byte)' ' }, 0, 2);
a++;
Thread.Sleep(50);
//Console.WriteLine("btr {0}", serialPort.BytesToRead);
if (serialPort.BytesToRead >= 2)
{
byte b1 = (byte)serialPort.ReadByte();
byte b2 = (byte)serialPort.ReadByte();
if (b1 == 0x14 && b2 == 0x10)
{
serialPort.Close();
return "1280";
}
}
}
serialPort.Close();
log.Warn("Not a 1280");
Thread.Sleep(500);
serialPort.DtrEnable = true;
serialPort.BaudRate = 115200;
serialPort.Open();
Thread.Sleep(100);
a = 0;
while (a < 4)
{
byte[] temp = new byte[] { 0x6, 0, 0, 0, 0 };
temp = ArduinoDetect.genstkv2packet(serialPort, temp);
a++;
Thread.Sleep(50);
try
{
if (temp[0] == 6 && temp[1] == 0 && temp.Length == 2)
{
serialPort.Close();
return "2560";
}
}
catch
{
}
}
serialPort.Close();
log.Warn("Not a 2560");
return "";
}
/// <summary>
/// Detects APM board version
/// </summary>
/// <param name="port"></param>
/// <returns> (1280/2560/2560-2)</returns>
public static string DetectBoard(string port)
{
SerialPort serialPort = new SerialPort();
serialPort.PortName = port;
if (serialPort.IsOpen)
serialPort.Close();
serialPort.DtrEnable = true;
serialPort.BaudRate = 57600;
serialPort.Open();
Thread.Sleep(100);
int a = 0;
while (a < 20) // 20 * 50 = 1 sec
{
//Console.WriteLine("write " + DateTime.Now.Millisecond);
serialPort.DiscardInBuffer();
serialPort.Write(new byte[] { (byte)'0', (byte)' ' }, 0, 2);
a++;
Thread.Sleep(50);
//Console.WriteLine("btr {0}", serialPort.BytesToRead);
if (serialPort.BytesToRead >= 2)
{
byte b1 = (byte)serialPort.ReadByte();
byte b2 = (byte)serialPort.ReadByte();
if (b1 == 0x14 && b2 == 0x10)
{
serialPort.Close();
return "1280";
}
}
}
serialPort.Close();
log.Warn("Not a 1280");
Thread.Sleep(500);
serialPort.DtrEnable = true;
serialPort.BaudRate = 115200;
serialPort.Open();
Thread.Sleep(100);
a = 0;
while (a < 4)
{
byte[] temp = new byte[] { 0x6, 0, 0, 0, 0 };
temp = ArduinoDetect.genstkv2packet(serialPort, temp);
a++;
Thread.Sleep(50);
try
{
if (temp[0] == 6 && temp[1] == 0 && temp.Length == 2)
{
serialPort.Close();
//HKEY_LOCAL_MACHINE\SYSTEM\CurrentControlSet\Enum\USB\VID_2341&PID_0010\640333439373519060F0\Device Parameters
if (!MainV2.MONO && !Thread.CurrentThread.CurrentUICulture.IsChildOf(CultureInfoEx.GetCultureInfo("zh-Hans")))
{
ObjectQuery query = new ObjectQuery("SELECT * FROM Win32_USBControllerDevice");
ManagementObjectSearcher searcher = new ManagementObjectSearcher(query);
foreach (ManagementObject obj2 in searcher.Get())
{
//Console.WriteLine("Dependant : " + obj2["Dependent"]);
// all apm 1-1.4 use a ftdi on the imu board.
if (obj2["Dependent"].ToString().Contains(@"USB\\VID_2341&PID_0010"))
{
return "2560-2";
}
}
return "2560";
}
else
{
if (DialogResult.Yes == CustomMessageBox.Show("Is this a APM 2?", "APM 2", MessageBoxButtons.YesNo))
{
return "2560-2";
}
else
{
return "2560";
}
}
}
}
catch { }
}
serialPort.Close();
log.Warn("Not a 2560");
return "";
}
public enum ap_var_type
{
AP_PARAM_NONE = 0,
AP_PARAM_INT8,
AP_PARAM_INT16,
AP_PARAM_INT32,
AP_PARAM_FLOAT,
AP_PARAM_VECTOR3F,
AP_PARAM_VECTOR6F,
AP_PARAM_MATRIX3F,
AP_PARAM_GROUP
};
static string[] type_names = new string[] {
"NONE", "INT8", "INT16", "INT32", "FLOAT", "VECTOR3F", "VECTOR6F","MATRIX6F", "GROUP"
};
static byte type_size(ap_var_type type)
{
switch (type) {
case ap_var_type.AP_PARAM_NONE:
case ap_var_type.AP_PARAM_GROUP:
return 0;
case ap_var_type.AP_PARAM_INT8:
return 1;
case ap_var_type.AP_PARAM_INT16:
return 2;
case ap_var_type.AP_PARAM_INT32:
return 4;
case ap_var_type.AP_PARAM_FLOAT:
return 4;
case ap_var_type.AP_PARAM_VECTOR3F:
return 3*4;
case ap_var_type.AP_PARAM_VECTOR6F:
return 6*4;
case ap_var_type.AP_PARAM_MATRIX3F:
return 3*3*4;
}
return 0;
}
/// <summary>
/// return the software id from eeprom
/// </summary>
/// <param name="comport">Port</param>
/// <param name="version">Board type</param>
/// <returns></returns>
public static int decodeApVar(string comport, string version)
{
ArduinoComms port = new ArduinoSTK();
if (version == "1280")
{
port = new ArduinoSTK();
port.BaudRate = 57600;
}
else if (version == "2560" || version == "2560-2")
{
port = new ArduinoSTKv2();
port.BaudRate = 115200;
}
else { return -1; }
port.PortName = comport;
port.DtrEnable = true;
port.Open();
port.connectAP();
byte[] buffer = port.download(1024 * 4);
port.Close();
if (buffer[0] != 'A' && buffer[0] != 'P' || buffer[1] != 'P' && buffer[1] != 'A') // this is the apvar header
{
return -1;
}
else
{
if (buffer[0] == 'A' && buffer[1] == 'P' && buffer[2] == 2)
{ // apvar header and version
int pos = 4;
byte key = 0;
while (pos < (1024 * 4))
{
int size = buffer[pos] & 63;
pos++;
key = buffer[pos];
pos++;
log.InfoFormat("{0:X4}: key {1} size {2}\n ", pos - 2, key, size + 1);
if (key == 0xff)
{
log.InfoFormat("end sentinal at {0}", pos - 2);
break;
}
if (key == 0)
{
//Array.Reverse(buffer, pos, 2);
return BitConverter.ToUInt16(buffer, pos);
}
for (int i = 0; i <= size; i++)
{
Console.Write(" {0:X2}", buffer[pos]);
pos++;
}
}
}
if (buffer[0] == 'P' && buffer[1] == 'A' && buffer[2] == 5) // ap param
{
int pos = 4;
byte key = 0;
while (pos < (1024 * 4))
{
key = buffer[pos];
pos++;
int group = buffer[pos];
pos++;
int type = buffer[pos];
pos++;
int size = type_size((ap_var_type)Enum.Parse(typeof(ap_var_type), type.ToString()));
Console.Write("{0:X4}: type {1} ({2}) key {3} group {4} size {5}\n ", pos - 2, type, type_names[type], key, group, size);
if (key == 0xff)
{
log.InfoFormat("end sentinal at {0}", pos - 2);
break;
}
if (key == 0)
{
//Array.Reverse(buffer, pos, 2);
return BitConverter.ToUInt16(buffer, pos);
}
for (int i = 0; i < size; i++)
{
Console.Write(" {0:X2}", buffer[pos]);
pos++;
}
}
}
}
return -1;
}
/// <summary>
/// STK v2 generate packet
/// </summary>
/// <param name="serialPort"></param>
/// <param name="message"></param>
/// <returns></returns>
static byte[] genstkv2packet(SerialPort serialPort, byte[] message)
{
byte[] data = new byte[300];
byte ck = 0;
data[0] = 0x1b;
ck ^= data[0];
data[1] = 0x1;
ck ^= data[1];
data[2] = (byte)((message.Length >> 8) & 0xff);
ck ^= data[2];
data[3] = (byte)(message.Length & 0xff);
ck ^= data[3];
data[4] = 0xe;
ck ^= data[4];
int a = 5;
foreach (byte let in message)
{
data[a] = let;
ck ^= let;
a++;
}
data[a] = ck;
a++;
serialPort.Write(data, 0, a);
//Console.WriteLine("about to read packet");
byte[] ret = ArduinoDetect.readpacket(serialPort);
//if (ret[1] == 0x0)
{
//Console.WriteLine("received OK");
}
return ret;
}
/// <summary>
///
/// </summary>
/// <param name="serialPort"></param>
/// <returns></returns>
static byte[] readpacket(SerialPort serialPort)
{
byte[] temp = new byte[4000];
byte[] mes = new byte[2] { 0x0, 0xC0 }; // fail
int a = 7;
int count = 0;
serialPort.ReadTimeout = 1000;
while (count < a)
{
//Console.WriteLine("count {0} a {1} mes leng {2}",count,a,mes.Length);
try
{
temp[count] = (byte)serialPort.ReadByte();
}
catch { break; }
//Console.Write("{1}", temp[0], (char)temp[0]);
if (temp[0] != 0x1b)
{
count = 0;
continue;
}
if (count == 3)
{
a = (temp[2] << 8) + temp[3];
mes = new byte[a];
a += 5;
}
if (count >= 5)
{
mes[count - 5] = temp[count];
}
count++;
}
//Console.WriteLine("read ck");
try
{
temp[count] = (byte)serialPort.ReadByte();
}
catch { }
count++;
Array.Resize<byte>(ref temp, count);
//Console.WriteLine(this.BytesToRead);
return mes;
}
}
}

View File

@ -1,335 +1,336 @@
using System;
using System.Collections.Generic;
using System.Reflection;
using System.Text;
using System.IO.Ports;
using System.Threading;
using log4net;
// Written by Michael Oborne
namespace ArdupilotMega
{
class ArduinoSTK : SerialPort, ArduinoComms
{
private static readonly ILog log = LogManager.GetLogger(MethodBase.GetCurrentMethod().DeclaringType);
public event ProgressEventHandler Progress;
public new void Open()
{
// default dtr status is false
//from http://svn.savannah.nongnu.org/viewvc/RELEASE_5_11_0/arduino.c?root=avrdude&view=markup
base.Open();
base.DtrEnable = false;
base.RtsEnable = false;
System.Threading.Thread.Sleep(50);
base.DtrEnable = true;
base.RtsEnable = true;
System.Threading.Thread.Sleep(50);
}
/// <summary>
/// Used to start initial connecting after serialport.open
/// </summary>
/// <returns>true = passed, false = failed</returns>
public bool connectAP()
{
if (!this.IsOpen)
{
return false;
}
int a = 0;
while (a < 50)
{
this.DiscardInBuffer();
this.Write(new byte[] { (byte)'0', (byte)' ' }, 0, 2);
a++;
Thread.Sleep(50);
log.InfoFormat("btr {0}", this.BytesToRead);
if (this.BytesToRead >= 2)
{
byte b1 = (byte)this.ReadByte();
byte b2 = (byte)this.ReadByte();
if (b1 == 0x14 && b2 == 0x10)
{
return true;
}
}
}
return false;
}
/// <summary>
/// Used to keep alive the connection
/// </summary>
/// <returns>true = passed, false = lost connection</returns>
public bool keepalive()
{
return connectAP();
}
/// <summary>
/// Syncs after a private command has been sent
/// </summary>
/// <returns>true = passed, false = failed</returns>
public bool sync()
{
if (!this.IsOpen)
{
return false;
}
this.ReadTimeout = 1000;
int f = 0;
while (this.BytesToRead < 1)
{
f++;
System.Threading.Thread.Sleep(1);
if (f > 1000)
return false;
}
int a = 0;
while (a < 10)
{
if (this.BytesToRead >= 2)
{
byte b1 = (byte)this.ReadByte();
byte b2 = (byte)this.ReadByte();
log.DebugFormat("bytes {0:X} {1:X}", b1, b2);
if (b1 == 0x14 && b2 == 0x10)
{
return true;
}
}
log.DebugFormat("btr {0}", this.BytesToRead);
Thread.Sleep(10);
a++;
}
return false;
}
/// <summary>
/// Downloads the eeprom with the given length - set Address first
/// </summary>
/// <param name="length">eeprom length</param>
/// <returns>downloaded data</returns>
public byte[] download(short length)
{
if (!this.IsOpen)
{
throw new Exception();
}
byte[] data = new byte[length];
byte[] command = new byte[] { (byte)'t', (byte)(length >> 8), (byte)(length & 0xff), (byte)'E', (byte)' ' };
this.Write(command, 0, command.Length);
if (this.ReadByte() == 0x14)
{ // 0x14
int step = 0;
while (step < length)
{
byte chr = (byte)this.ReadByte();
data[step] = chr;
step++;
}
if (this.ReadByte() != 0x10) // 0x10
throw new Exception("Lost Sync 0x10");
}
else
{
throw new Exception("Lost Sync 0x14");
}
return data;
}
public byte[] downloadflash(short length)
{
if (!this.IsOpen)
{
throw new Exception("Port Not Open");
}
byte[] data = new byte[length];
this.ReadTimeout = 1000;
byte[] command = new byte[] { (byte)'t', (byte)(length >> 8), (byte)(length & 0xff), (byte)'F', (byte)' ' };
this.Write(command, 0, command.Length);
if (this.ReadByte() == 0x14)
{ // 0x14
int read = length;
while (read > 0)
{
//Console.WriteLine("offset {0} read {1}", length - read, read);
read -= this.Read(data, length - read, read);
//System.Threading.Thread.Sleep(1);
}
if (this.ReadByte() != 0x10) // 0x10
throw new Exception("Lost Sync 0x10");
}
else
{
throw new Exception("Lost Sync 0x14");
}
return data;
}
public bool uploadflash(byte[] data, int startfrom, int length, int startaddress)
{
if (!this.IsOpen)
{
return false;
}
int loops = (length / 0x100);
int totalleft = length;
int sending = 0;
for (int a = 0; a <= loops; a++)
{
if (totalleft > 0x100)
{
sending = 0x100;
}
else
{
sending = totalleft;
}
//startaddress = 256;
if (sending == 0)
return true;
setaddress(startaddress);
startaddress += sending;
byte[] command = new byte[] { (byte)'d', (byte)(sending >> 8), (byte)(sending & 0xff), (byte)'F' };
this.Write(command, 0, command.Length);
log.Info((startfrom + (length - totalleft)) + " - " + sending);
this.Write(data, startfrom + (length - totalleft), sending);
command = new byte[] { (byte)' ' };
this.Write(command, 0, command.Length);
totalleft -= sending;
if (Progress != null)
Progress((int)(((float)startaddress / (float)length) * 100),"");
if (!sync())
{
log.Info("No Sync");
return false;
}
}
return true;
}
/// <summary>
/// Sets the eeprom start read or write address
/// </summary>
/// <param name="address">address, must be eaven number</param>
/// <returns>true = passed, false = failed</returns>
public bool setaddress(int address)
{
if (!this.IsOpen)
{
return false;
}
if (address % 2 == 1)
{
throw new Exception("Address must be an even number");
}
log.Info("Sending address " + ((ushort)(address / 2)));
address /= 2;
address = (ushort)address;
byte[] command = new byte[] { (byte)'U', (byte)(address & 0xff), (byte)(address >> 8), (byte)' ' };
this.Write(command, 0, command.Length);
return sync();
}
/// <summary>
/// Upload data at preset address
/// </summary>
/// <param name="data">array to read from</param>
/// <param name="startfrom">start array index</param>
/// <param name="length">length to send</param>
/// <param name="startaddress">sets eeprom start programing address</param>
/// <returns>true = passed, false = failed</returns>
public bool upload(byte[] data, short startfrom, short length, short startaddress)
{
if (!this.IsOpen)
{
return false;
}
int loops = (length / 0x100);
int totalleft = length;
int sending = 0;
for (int a = 0; a <= loops; a++)
{
if (totalleft > 0x100)
{
sending = 0x100;
}
else
{
sending = totalleft;
}
if (sending == 0)
return true;
setaddress(startaddress);
startaddress += (short)sending;
byte[] command = new byte[] { (byte)'d', (byte)(sending >> 8), (byte)(sending & 0xff), (byte)'E' };
this.Write(command, 0, command.Length);
log.Info((startfrom + (length - totalleft)) + " - " + sending);
this.Write(data, startfrom + (length - totalleft), sending);
command = new byte[] { (byte)' ' };
this.Write(command, 0, command.Length);
totalleft -= sending;
if (!sync())
{
log.Info("No Sync");
return false;
}
}
return true;
}
public new bool Close()
{
try
{
byte[] command = new byte[] { (byte)'Q', (byte)' ' };
this.Write(command, 0, command.Length);
}
catch { }
if (base.IsOpen)
base.Close();
this.DtrEnable = false;
this.RtsEnable = false;
return true;
}
}
using System;
using System.Collections.Generic;
using System.Reflection;
using System.Text;
using System.Threading;
using log4net;
using ArdupilotMega.Comms;
// Written by Michael Oborne
namespace ArdupilotMega.Arduino
{
class ArduinoSTK : SerialPort, ArduinoComms
{
private static readonly ILog log = LogManager.GetLogger(MethodBase.GetCurrentMethod().DeclaringType);
public event ProgressEventHandler Progress;
public new void Open()
{
// default dtr status is false
//from http://svn.savannah.nongnu.org/viewvc/RELEASE_5_11_0/arduino.c?root=avrdude&view=markup
base.Open();
base.DtrEnable = false;
base.RtsEnable = false;
System.Threading.Thread.Sleep(50);
base.DtrEnable = true;
base.RtsEnable = true;
System.Threading.Thread.Sleep(50);
}
/// <summary>
/// Used to start initial connecting after serialport.open
/// </summary>
/// <returns>true = passed, false = failed</returns>
public bool connectAP()
{
if (!this.IsOpen)
{
return false;
}
int a = 0;
while (a < 50)
{
this.DiscardInBuffer();
this.Write(new byte[] { (byte)'0', (byte)' ' }, 0, 2);
a++;
Thread.Sleep(50);
log.InfoFormat("btr {0}", this.BytesToRead);
if (this.BytesToRead >= 2)
{
byte b1 = (byte)this.ReadByte();
byte b2 = (byte)this.ReadByte();
if (b1 == 0x14 && b2 == 0x10)
{
return true;
}
}
}
return false;
}
/// <summary>
/// Used to keep alive the connection
/// </summary>
/// <returns>true = passed, false = lost connection</returns>
public bool keepalive()
{
return connectAP();
}
/// <summary>
/// Syncs after a private command has been sent
/// </summary>
/// <returns>true = passed, false = failed</returns>
public bool sync()
{
if (!this.IsOpen)
{
return false;
}
this.ReadTimeout = 1000;
int f = 0;
while (this.BytesToRead < 1)
{
f++;
System.Threading.Thread.Sleep(1);
if (f > 1000)
return false;
}
int a = 0;
while (a < 10)
{
if (this.BytesToRead >= 2)
{
byte b1 = (byte)this.ReadByte();
byte b2 = (byte)this.ReadByte();
log.DebugFormat("bytes {0:X} {1:X}", b1, b2);
if (b1 == 0x14 && b2 == 0x10)
{
return true;
}
}
log.DebugFormat("btr {0}", this.BytesToRead);
Thread.Sleep(10);
a++;
}
return false;
}
/// <summary>
/// Downloads the eeprom with the given length - set Address first
/// </summary>
/// <param name="length">eeprom length</param>
/// <returns>downloaded data</returns>
public byte[] download(short length)
{
if (!this.IsOpen)
{
throw new Exception();
}
byte[] data = new byte[length];
byte[] command = new byte[] { (byte)'t', (byte)(length >> 8), (byte)(length & 0xff), (byte)'E', (byte)' ' };
this.Write(command, 0, command.Length);
if (this.ReadByte() == 0x14)
{ // 0x14
int step = 0;
while (step < length)
{
byte chr = (byte)this.ReadByte();
data[step] = chr;
step++;
}
if (this.ReadByte() != 0x10) // 0x10
throw new Exception("Lost Sync 0x10");
}
else
{
throw new Exception("Lost Sync 0x14");
}
return data;
}
public byte[] downloadflash(short length)
{
if (!this.IsOpen)
{
throw new Exception("Port Not Open");
}
byte[] data = new byte[length];
this.ReadTimeout = 1000;
byte[] command = new byte[] { (byte)'t', (byte)(length >> 8), (byte)(length & 0xff), (byte)'F', (byte)' ' };
this.Write(command, 0, command.Length);
if (this.ReadByte() == 0x14)
{ // 0x14
int read = length;
while (read > 0)
{
//Console.WriteLine("offset {0} read {1}", length - read, read);
read -= this.Read(data, length - read, read);
//System.Threading.Thread.Sleep(1);
}
if (this.ReadByte() != 0x10) // 0x10
throw new Exception("Lost Sync 0x10");
}
else
{
throw new Exception("Lost Sync 0x14");
}
return data;
}
public bool uploadflash(byte[] data, int startfrom, int length, int startaddress)
{
if (!this.IsOpen)
{
return false;
}
int loops = (length / 0x100);
int totalleft = length;
int sending = 0;
for (int a = 0; a <= loops; a++)
{
if (totalleft > 0x100)
{
sending = 0x100;
}
else
{
sending = totalleft;
}
//startaddress = 256;
if (sending == 0)
return true;
setaddress(startaddress);
startaddress += sending;
byte[] command = new byte[] { (byte)'d', (byte)(sending >> 8), (byte)(sending & 0xff), (byte)'F' };
this.Write(command, 0, command.Length);
log.Info((startfrom + (length - totalleft)) + " - " + sending);
this.Write(data, startfrom + (length - totalleft), sending);
command = new byte[] { (byte)' ' };
this.Write(command, 0, command.Length);
totalleft -= sending;
if (Progress != null)
Progress((int)(((float)startaddress / (float)length) * 100),"");
if (!sync())
{
log.Info("No Sync");
return false;
}
}
return true;
}
/// <summary>
/// Sets the eeprom start read or write address
/// </summary>
/// <param name="address">address, must be eaven number</param>
/// <returns>true = passed, false = failed</returns>
public bool setaddress(int address)
{
if (!this.IsOpen)
{
return false;
}
if (address % 2 == 1)
{
throw new Exception("Address must be an even number");
}
log.Info("Sending address " + ((ushort)(address / 2)));
address /= 2;
address = (ushort)address;
byte[] command = new byte[] { (byte)'U', (byte)(address & 0xff), (byte)(address >> 8), (byte)' ' };
this.Write(command, 0, command.Length);
return sync();
}
/// <summary>
/// Upload data at preset address
/// </summary>
/// <param name="data">array to read from</param>
/// <param name="startfrom">start array index</param>
/// <param name="length">length to send</param>
/// <param name="startaddress">sets eeprom start programing address</param>
/// <returns>true = passed, false = failed</returns>
public bool upload(byte[] data, short startfrom, short length, short startaddress)
{
if (!this.IsOpen)
{
return false;
}
int loops = (length / 0x100);
int totalleft = length;
int sending = 0;
for (int a = 0; a <= loops; a++)
{
if (totalleft > 0x100)
{
sending = 0x100;
}
else
{
sending = totalleft;
}
if (sending == 0)
return true;
setaddress(startaddress);
startaddress += (short)sending;
byte[] command = new byte[] { (byte)'d', (byte)(sending >> 8), (byte)(sending & 0xff), (byte)'E' };
this.Write(command, 0, command.Length);
log.Info((startfrom + (length - totalleft)) + " - " + sending);
this.Write(data, startfrom + (length - totalleft), sending);
command = new byte[] { (byte)' ' };
this.Write(command, 0, command.Length);
totalleft -= sending;
if (!sync())
{
log.Info("No Sync");
return false;
}
}
return true;
}
public new bool Close()
{
try
{
byte[] command = new byte[] { (byte)'Q', (byte)' ' };
this.Write(command, 0, command.Length);
}
catch { }
if (base.IsOpen)
base.Close();
this.DtrEnable = false;
this.RtsEnable = false;
return true;
}
}
}

View File

@ -1,388 +1,388 @@
using System;
using System.Collections.Generic;
using System.Reflection;
using System.Text;
using System.IO.Ports;
using System.Threading;
using log4net;
// Written by Michael Oborne
namespace ArdupilotMega
{
class ArduinoSTKv2 : SerialPort,ArduinoComms
{
private static readonly ILog log = LogManager.GetLogger(MethodBase.GetCurrentMethod().DeclaringType);
public event ProgressEventHandler Progress;
public new void Open()
{
// default dtr status is false
//from http://svn.savannah.nongnu.org/viewvc/RELEASE_5_11_0/arduino.c?root=avrdude&view=markup
base.Open();
base.DtrEnable = false;
base.RtsEnable = false;
System.Threading.Thread.Sleep(50);
base.DtrEnable = true;
base.RtsEnable = true;
System.Threading.Thread.Sleep(50);
}
public byte[] genstkv2packet(byte[] message)
{
byte[] data = new byte[300];
byte ck = 0;
data[0] = 0x1b;
ck ^= data[0];
data[1] = 0x1;
ck ^= data[1];
data[2] = (byte)((message.Length >> 8) & 0xff);
ck ^= data[2];
data[3] = (byte)(message.Length & 0xff);
ck ^= data[3];
data[4] = 0xe;
ck ^= data[4];
int a = 5;
foreach (byte let in message)
{
data[a] = let;
ck ^= let;
a++;
}
data[a] = ck;
a++;
this.Write(data,0,a);
//Console.WriteLine("about to read packet");
byte[] ret = readpacket();
//if (ret[1] == 0x0)
{
//Console.WriteLine("received OK");
}
return ret;
}
byte[] readpacket()
{
byte[] temp = new byte[4000];
byte[] mes = new byte[2] { 0x0, 0xC0 }; // fail
int a = 7;
int count = 0;
this.ReadTimeout = 1000;
while (count < a)
{
//Console.WriteLine("count {0} a {1} mes leng {2}",count,a,mes.Length);
try
{
temp[count] = (byte)this.ReadByte();
}
catch { break; }
//Console.Write("{1}", temp[0], (char)temp[0]);
if (temp[0] != 0x1b)
{
count = 0;
continue;
}
if (count == 3)
{
a = (temp[2] << 8) + temp[3];
mes = new byte[a];
a += 5;
}
if (count >= 5)
{
mes[count - 5] = temp[count];
}
count++;
}
//Console.WriteLine("read ck");
try
{
temp[count] = (byte)this.ReadByte();
}
catch { }
count++;
Array.Resize<byte>(ref temp, count);
//Console.WriteLine(this.BytesToRead);
return mes;
}
/// <summary>
/// Used to start initial connecting after serialport.open
/// </summary>
/// <returns>true = passed, false = failed</returns>
public bool connectAP()
{
if (!this.IsOpen)
{
return false;
}
Thread.Sleep(100);
int a = 0;
while (a < 5)
{
byte[] temp = new byte[] { 0x6, 0,0,0,0};
temp = this.genstkv2packet(temp);
a++;
Thread.Sleep(50);
try
{
if (temp[0] == 6 && temp[1] == 0 && temp.Length == 2)
{
return true;
}
}
catch { }
}
return false;
}
/// <summary>
/// Used to keep alive the connection
/// </summary>
/// <returns>true = passed, false = lost connection</returns>
public bool keepalive()
{
return connectAP();
}
/// <summary>
/// Syncs after a private command has been sent
/// </summary>
/// <returns>true = passed, false = failed</returns>
public bool sync()
{
if (!this.IsOpen)
{
return false;
}
return true;
}
/// <summary>
/// Downloads the eeprom with the given length - set Address first
/// </summary>
/// <param name="length">eeprom length</param>
/// <returns>downloaded data</returns>
public byte[] download(short length)
{
if (!this.IsOpen)
{
throw new Exception();
}
byte[] data = new byte[length];
byte[] temp = new byte[] { 0x16, (byte)((length >> 8) & 0xff), (byte)((length >> 0) & 0xff) };
temp = this.genstkv2packet(temp);
Array.Copy(temp, 2, data, 0, length);
return data;
}
public byte[] downloadflash(short length)
{
if (!this.IsOpen)
{
throw new Exception("Port Closed");
}
byte[] data = new byte[length];
byte[] temp = new byte[] { 0x14, (byte)((length >> 8) & 0xff), (byte)((length >> 0) & 0xff) };
temp = this.genstkv2packet(temp);
Array.Copy(temp, 2, data, 0, length);
return data;
}
public bool uploadflash(byte[] data, int startfrom, int length, int startaddress)
{
if (!this.IsOpen)
{
return false;
}
int loops = (length / 0x100);
int totalleft = length;
int sending = 0;
for (int a = 0; a <= loops; a++)
{
if (totalleft > 0x100)
{
sending = 0x100;
}
else
{
sending = totalleft;
}
//startaddress = 256;
if (sending == 0)
return true;
setaddress(startaddress);
startaddress += sending;
// 0x13
byte[] command = new byte[] { (byte)0x13, (byte)(sending >> 8), (byte)(sending & 0xff) };
log.InfoFormat((startfrom + (length - totalleft)) + " - " + sending);
Array.Resize<byte>(ref command, sending + 10); // sending + head
Array.Copy(data, startfrom + (length - totalleft), command, 10, sending);
command = this.genstkv2packet(command);
totalleft -= sending;
if (Progress != null)
Progress((int)(((float)startaddress / (float)length) * 100),"");
if (command[1] != 0)
{
log.InfoFormat("No Sync");
return false;
}
}
return true;
}
/// <summary>
/// Sets the eeprom start read or write address
/// </summary>
/// <param name="address">address, must be eaven number</param>
/// <returns>true = passed, false = failed</returns>
public bool setaddress(int address)
{
if (!this.IsOpen)
{
return false;
}
if (address % 2 == 1)
{
throw new Exception("Address must be an even number");
}
log.InfoFormat("Sending address " + ((address / 2)));
int tempstart = address / 2; // words
byte[] temp = new byte[] { 0x6, (byte)((tempstart >> 24) & 0xff), (byte)((tempstart >> 16) & 0xff), (byte)((tempstart >> 8) & 0xff), (byte)((tempstart >> 0) & 0xff) };
temp = this.genstkv2packet(temp);
if (temp[1] == 0)
{
return true;
}
return false;
}
/// <summary>
/// Upload data at preset address
/// </summary>
/// <param name="data">array to read from</param>
/// <param name="startfrom">start array index</param>
/// <param name="length">length to send</param>
/// <param name="startaddress">sets eeprom start programing address</param>
/// <returns>true = passed, false = failed</returns>
public bool upload(byte[] data,short startfrom,short length, short startaddress)
{
if (!this.IsOpen)
{
return false;
}
int loops = (length / 0x100);
int totalleft = length;
int sending = 0;
for (int a = 0; a <= loops; a++)
{
if (totalleft > 0x100)
{
sending = 0x100;
}
else
{
sending = totalleft;
}
//startaddress = 256;
if (sending == 0)
return true;
setaddress(startaddress);
startaddress += (short)sending;
// 0x13
byte[] command = new byte[] { (byte)0x15, (byte)(sending >> 8), (byte)(sending & 0xff) };
log.InfoFormat((startfrom + (length - totalleft)) + " - " + sending);
Array.Resize<byte>(ref command, sending + 10); // sending + head
Array.Copy(data, startfrom + (length - totalleft), command, 10, sending);
command = this.genstkv2packet(command);
totalleft -= sending;
if (Progress != null)
Progress((int)(((float)startaddress / (float)length) * 100),"");
if (command[1] != 0)
{
log.InfoFormat("No Sync");
return false;
}
}
return true;
}
public new bool Close() {
try
{
byte[] command = new byte[] { (byte)0x11 };
genstkv2packet(command);
}
catch { }
if (base.IsOpen)
base.Close();
base.DtrEnable = false;
base.RtsEnable = false;
return true;
}
}
}
using System;
using System.Collections.Generic;
using System.Reflection;
using System.Text;
using System.IO.Ports;
using System.Threading;
using log4net;
// Written by Michael Oborne
namespace ArdupilotMega.Arduino
{
class ArduinoSTKv2 : SerialPort,ArduinoComms
{
private static readonly ILog log = LogManager.GetLogger(MethodBase.GetCurrentMethod().DeclaringType);
public event ProgressEventHandler Progress;
public new void Open()
{
// default dtr status is false
//from http://svn.savannah.nongnu.org/viewvc/RELEASE_5_11_0/arduino.c?root=avrdude&view=markup
base.Open();
base.DtrEnable = false;
base.RtsEnable = false;
System.Threading.Thread.Sleep(50);
base.DtrEnable = true;
base.RtsEnable = true;
System.Threading.Thread.Sleep(50);
}
public byte[] genstkv2packet(byte[] message)
{
byte[] data = new byte[300];
byte ck = 0;
data[0] = 0x1b;
ck ^= data[0];
data[1] = 0x1;
ck ^= data[1];
data[2] = (byte)((message.Length >> 8) & 0xff);
ck ^= data[2];
data[3] = (byte)(message.Length & 0xff);
ck ^= data[3];
data[4] = 0xe;
ck ^= data[4];
int a = 5;
foreach (byte let in message)
{
data[a] = let;
ck ^= let;
a++;
}
data[a] = ck;
a++;
this.Write(data,0,a);
//Console.WriteLine("about to read packet");
byte[] ret = readpacket();
//if (ret[1] == 0x0)
{
//Console.WriteLine("received OK");
}
return ret;
}
byte[] readpacket()
{
byte[] temp = new byte[4000];
byte[] mes = new byte[2] { 0x0, 0xC0 }; // fail
int a = 7;
int count = 0;
this.ReadTimeout = 1000;
while (count < a)
{
//Console.WriteLine("count {0} a {1} mes leng {2}",count,a,mes.Length);
try
{
temp[count] = (byte)this.ReadByte();
}
catch { break; }
//Console.Write("{1}", temp[0], (char)temp[0]);
if (temp[0] != 0x1b)
{
count = 0;
continue;
}
if (count == 3)
{
a = (temp[2] << 8) + temp[3];
mes = new byte[a];
a += 5;
}
if (count >= 5)
{
mes[count - 5] = temp[count];
}
count++;
}
//Console.WriteLine("read ck");
try
{
temp[count] = (byte)this.ReadByte();
}
catch { }
count++;
Array.Resize<byte>(ref temp, count);
//Console.WriteLine(this.BytesToRead);
return mes;
}
/// <summary>
/// Used to start initial connecting after serialport.open
/// </summary>
/// <returns>true = passed, false = failed</returns>
public bool connectAP()
{
if (!this.IsOpen)
{
return false;
}
Thread.Sleep(100);
int a = 0;
while (a < 5)
{
byte[] temp = new byte[] { 0x6, 0,0,0,0};
temp = this.genstkv2packet(temp);
a++;
Thread.Sleep(50);
try
{
if (temp[0] == 6 && temp[1] == 0 && temp.Length == 2)
{
return true;
}
}
catch { }
}
return false;
}
/// <summary>
/// Used to keep alive the connection
/// </summary>
/// <returns>true = passed, false = lost connection</returns>
public bool keepalive()
{
return connectAP();
}
/// <summary>
/// Syncs after a private command has been sent
/// </summary>
/// <returns>true = passed, false = failed</returns>
public bool sync()
{
if (!this.IsOpen)
{
return false;
}
return true;
}
/// <summary>
/// Downloads the eeprom with the given length - set Address first
/// </summary>
/// <param name="length">eeprom length</param>
/// <returns>downloaded data</returns>
public byte[] download(short length)
{
if (!this.IsOpen)
{
throw new Exception();
}
byte[] data = new byte[length];
byte[] temp = new byte[] { 0x16, (byte)((length >> 8) & 0xff), (byte)((length >> 0) & 0xff) };
temp = this.genstkv2packet(temp);
Array.Copy(temp, 2, data, 0, length);
return data;
}
public byte[] downloadflash(short length)
{
if (!this.IsOpen)
{
throw new Exception("Port Closed");
}
byte[] data = new byte[length];
byte[] temp = new byte[] { 0x14, (byte)((length >> 8) & 0xff), (byte)((length >> 0) & 0xff) };
temp = this.genstkv2packet(temp);
Array.Copy(temp, 2, data, 0, length);
return data;
}
public bool uploadflash(byte[] data, int startfrom, int length, int startaddress)
{
if (!this.IsOpen)
{
return false;
}
int loops = (length / 0x100);
int totalleft = length;
int sending = 0;
for (int a = 0; a <= loops; a++)
{
if (totalleft > 0x100)
{
sending = 0x100;
}
else
{
sending = totalleft;
}
//startaddress = 256;
if (sending == 0)
return true;
setaddress(startaddress);
startaddress += sending;
// 0x13
byte[] command = new byte[] { (byte)0x13, (byte)(sending >> 8), (byte)(sending & 0xff) };
log.InfoFormat((startfrom + (length - totalleft)) + " - " + sending);
Array.Resize<byte>(ref command, sending + 10); // sending + head
Array.Copy(data, startfrom + (length - totalleft), command, 10, sending);
command = this.genstkv2packet(command);
totalleft -= sending;
if (Progress != null)
Progress((int)(((float)startaddress / (float)length) * 100),"");
if (command[1] != 0)
{
log.InfoFormat("No Sync");
return false;
}
}
return true;
}
/// <summary>
/// Sets the eeprom start read or write address
/// </summary>
/// <param name="address">address, must be eaven number</param>
/// <returns>true = passed, false = failed</returns>
public bool setaddress(int address)
{
if (!this.IsOpen)
{
return false;
}
if (address % 2 == 1)
{
throw new Exception("Address must be an even number");
}
log.InfoFormat("Sending address " + ((address / 2)));
int tempstart = address / 2; // words
byte[] temp = new byte[] { 0x6, (byte)((tempstart >> 24) & 0xff), (byte)((tempstart >> 16) & 0xff), (byte)((tempstart >> 8) & 0xff), (byte)((tempstart >> 0) & 0xff) };
temp = this.genstkv2packet(temp);
if (temp[1] == 0)
{
return true;
}
return false;
}
/// <summary>
/// Upload data at preset address
/// </summary>
/// <param name="data">array to read from</param>
/// <param name="startfrom">start array index</param>
/// <param name="length">length to send</param>
/// <param name="startaddress">sets eeprom start programing address</param>
/// <returns>true = passed, false = failed</returns>
public bool upload(byte[] data,short startfrom,short length, short startaddress)
{
if (!this.IsOpen)
{
return false;
}
int loops = (length / 0x100);
int totalleft = length;
int sending = 0;
for (int a = 0; a <= loops; a++)
{
if (totalleft > 0x100)
{
sending = 0x100;
}
else
{
sending = totalleft;
}
//startaddress = 256;
if (sending == 0)
return true;
setaddress(startaddress);
startaddress += (short)sending;
// 0x13
byte[] command = new byte[] { (byte)0x15, (byte)(sending >> 8), (byte)(sending & 0xff) };
log.InfoFormat((startfrom + (length - totalleft)) + " - " + sending);
Array.Resize<byte>(ref command, sending + 10); // sending + head
Array.Copy(data, startfrom + (length - totalleft), command, 10, sending);
command = this.genstkv2packet(command);
totalleft -= sending;
if (Progress != null)
Progress((int)(((float)startaddress / (float)length) * 100),"");
if (command[1] != 0)
{
log.InfoFormat("No Sync");
return false;
}
}
return true;
}
public new bool Close() {
try
{
byte[] command = new byte[] { (byte)0x11 };
genstkv2packet(command);
}
catch { }
if (base.IsOpen)
base.Close();
base.DtrEnable = false;
base.RtsEnable = false;
return true;
}
}
}

View File

@ -355,7 +355,7 @@
<Compile Include="Controls\AGauge.cs">
<SubType>UserControl</SubType>
</Compile>
<Compile Include="ArduinoDetect.cs" />
<Compile Include="Arduino\ArduinoDetect.cs" />
<Compile Include="AviWriter.cs" />
<Compile Include="Camera.cs">
<SubType>Form</SubType>
@ -364,12 +364,12 @@
<DependentUpon>Camera.cs</DependentUpon>
</Compile>
<Compile Include="Capture.cs" />
<Compile Include="CommsSerialInterface.cs" />
<Compile Include="CommsSerialPort.cs">
<Compile Include="Comms\CommsSerialInterface.cs" />
<Compile Include="Comms\CommsSerialPort.cs">
<SubType>Component</SubType>
</Compile>
<Compile Include="CommsTCPSerial.cs" />
<Compile Include="CommsUdpSerial.cs" />
<Compile Include="Comms\CommsTCPSerial.cs" />
<Compile Include="Comms\CommsUdpSerial.cs" />
<Compile Include="Controls\ImageLabel.cs">
<SubType>UserControl</SubType>
</Compile>
@ -379,12 +379,6 @@
<Compile Include="Controls\myGMAP.cs">
<SubType>UserControl</SubType>
</Compile>
<Compile Include="Controls\XorPlus.cs">
<SubType>Form</SubType>
</Compile>
<Compile Include="Controls\XorPlus.Designer.cs">
<DependentUpon>XorPlus.cs</DependentUpon>
</Compile>
<Compile Include="Radio\IHex.cs" />
<Compile Include="Mavlink\MavlinkCRC.cs" />
<Compile Include="Mavlink\MavlinkUtil.cs" />
@ -439,14 +433,14 @@
<Compile Include="Common.cs">
<SubType>Component</SubType>
</Compile>
<Compile Include="ArduinoComms.cs" />
<Compile Include="Arduino\ArduinoComms.cs" />
<Compile Include="Controls\MyLabel.cs">
<SubType>Component</SubType>
</Compile>
<Compile Include="Controls\MyUserControl.cs">
<SubType>UserControl</SubType>
</Compile>
<Compile Include="ArduinoSTKv2.cs">
<Compile Include="Arduino\ArduinoSTKv2.cs">
<SubType>Component</SubType>
</Compile>
<Compile Include="paramcompare.cs">
@ -473,7 +467,7 @@
<Compile Include="GCSViews\Terminal.Designer.cs">
<DependentUpon>Terminal.cs</DependentUpon>
</Compile>
<Compile Include="HUD.cs">
<Compile Include="Controls\HUD.cs">
<SubType>UserControl</SubType>
</Compile>
<Compile Include="MainV2.cs">
@ -515,7 +509,7 @@
<DependentUpon>ElevationProfile.cs</DependentUpon>
</Compile>
<Compile Include="MAVLink.cs" />
<Compile Include="ArduinoSTK.cs">
<Compile Include="Arduino\ArduinoSTK.cs">
<SubType>Component</SubType>
</Compile>
<Compile Include="Log.cs">
@ -760,9 +754,6 @@
<EmbeddedResource Include="Controls\ImageLabel.resx">
<DependentUpon>ImageLabel.cs</DependentUpon>
</EmbeddedResource>
<EmbeddedResource Include="Controls\XorPlus.resx">
<DependentUpon>XorPlus.cs</DependentUpon>
</EmbeddedResource>
<EmbeddedResource Include="GCSViews\Configuration.es-ES.resx">
<DependentUpon>Configuration.cs</DependentUpon>
</EmbeddedResource>
@ -1024,6 +1015,7 @@
</EmbeddedResource>
<EmbeddedResource Include="GCSViews\Simulation.resx">
<DependentUpon>Simulation.cs</DependentUpon>
<SubType>Designer</SubType>
</EmbeddedResource>
<EmbeddedResource Include="GCSViews\Simulation.zh-Hans.resx">
<DependentUpon>Simulation.cs</DependentUpon>
@ -1099,10 +1091,6 @@
<None Include="m3u\networklink.kml">
<CopyToOutputDirectory>Always</CopyToOutputDirectory>
</None>
<None Include="MAC\Info.plist" />
<None Include="MAC\run.sh" />
<None Include="Msi\installer.bat" />
<None Include="Msi\installer.wxs" />
<None Include="mykey.snk" />
<None Include="Properties\app.manifest" />
<None Include="Properties\DataSources\CurrentState.datasource" />

View File

@ -61,7 +61,7 @@
this.TXT_distacflphotos = new System.Windows.Forms.TextBox();
this.TXT_distflphotos = new System.Windows.Forms.TextBox();
this.CMB_camera = new System.Windows.Forms.ComboBox();
this.BUT_save = new ArdupilotMega.MyButton();
this.BUT_save = new ArdupilotMega.Controls.MyButton();
((System.ComponentModel.ISupportInitialize)(this.num_agl)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.num_focallength)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.num_overlap)).BeginInit();
@ -379,6 +379,6 @@
private System.Windows.Forms.TextBox TXT_distacflphotos;
private System.Windows.Forms.TextBox TXT_distflphotos;
private System.Windows.Forms.ComboBox CMB_camera;
private MyButton BUT_save;
private ArdupilotMega.Controls.MyButton BUT_save;
}
}

View File

@ -915,7 +915,7 @@
<value>BUT_save</value>
</data>
<data name="&gt;&gt;BUT_save.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null</value>
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;BUT_save.Parent" xml:space="preserve">
<value>$this</value>

View File

@ -1,5 +1,6 @@
using System;
using System.Collections.Generic;
using System.Linq;
using System.ComponentModel;
using System.Data;
using System.Drawing;
@ -23,6 +24,7 @@ using log4net;
using ZedGraph; // Graphs
using ArdupilotMega;
using System.Reflection;
using ArdupilotMega.Utilities;
using System.IO;
@ -710,6 +712,22 @@ namespace ArdupilotMega
return null;
}
public static List<KeyValuePair<int,string>> getModesList()
{
if (MainV2.cs.firmware == MainV2.Firmwares.ArduPlane)
{
var flightModes = EnumTranslator.Translate<apmmodes>();
return flightModes.ToList();
}
else if (MainV2.cs.firmware == MainV2.Firmwares.ArduCopter2)
{
var flightModes = EnumTranslator.Translate<ac2modes>();
return flightModes.ToList();
}
return null;
}
public static Form LoadingBox(string title, string promptText)
{
Form form = new Form();
@ -746,7 +764,7 @@ namespace ArdupilotMega
Form form = new Form();
System.Windows.Forms.Label label = new System.Windows.Forms.Label();
CheckBox chk = new CheckBox();
MyButton buttonOk = new MyButton();
ArdupilotMega.Controls.MyButton buttonOk = new ArdupilotMega.Controls.MyButton();
System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(MainV2));
form.Icon = ((System.Drawing.Icon)(resources.GetObject("$this.Icon")));
@ -806,8 +824,8 @@ namespace ArdupilotMega
Form form = new Form();
System.Windows.Forms.Label label = new System.Windows.Forms.Label();
TextBox textBox = new TextBox();
MyButton buttonOk = new MyButton();
MyButton buttonCancel = new MyButton();
ArdupilotMega.Controls.MyButton buttonOk = new ArdupilotMega.Controls.MyButton();
ArdupilotMega.Controls.MyButton buttonCancel = new ArdupilotMega.Controls.MyButton();
form.TopMost = true;

View File

@ -1,59 +1,59 @@
using System;
using System.Collections.Generic;
using System.Text;
using System.IO.Ports;
using System.IO;
using System.Reflection;
namespace ArdupilotMega
{
public interface ICommsSerial
{
// from serialport class
// Methods
void Close();
void DiscardInBuffer();
//void DiscardOutBuffer();
void Open();
int Read(byte[] buffer, int offset, int count);
//int Read(char[] buffer, int offset, int count);
int ReadByte();
int ReadChar();
string ReadExisting();
string ReadLine();
//string ReadTo(string value);
void Write(string text);
void Write(byte[] buffer, int offset, int count);
//void Write(char[] buffer, int offset, int count);
void WriteLine(string text);
void toggleDTR();
// Properties
//Stream BaseStream { get; }
int BaudRate { get; set; }
//bool BreakState { get; set; }
int BytesToRead { get; }
int BytesToWrite { get; }
//bool CDHolding { get; }
//bool CtsHolding { get; }
int DataBits { get; set; }
//bool DiscardNull { get; set; }
//bool DsrHolding { get; }
bool DtrEnable { get; set; }
//Encoding Encoding { get; set; }
//Handshake Handshake { get; set; }
bool IsOpen { get; }
//string NewLine { get; set; }
Parity Parity { get; set; }
//byte ParityReplace { get; set; }
string PortName { get; set; }
int ReadBufferSize { get; set; }
int ReadTimeout { get; set; }
int ReceivedBytesThreshold { get; set; }
bool RtsEnable { get; set; }
StopBits StopBits { get; set; }
int WriteBufferSize { get; set; }
int WriteTimeout { get; set; }
}
}
using System;
using System.Collections.Generic;
using System.Text;
using System.IO.Ports;
using System.IO;
using System.Reflection;
namespace ArdupilotMega.Comms
{
public interface ICommsSerial
{
// from serialport class
// Methods
void Close();
void DiscardInBuffer();
//void DiscardOutBuffer();
void Open();
int Read(byte[] buffer, int offset, int count);
//int Read(char[] buffer, int offset, int count);
int ReadByte();
int ReadChar();
string ReadExisting();
string ReadLine();
//string ReadTo(string value);
void Write(string text);
void Write(byte[] buffer, int offset, int count);
//void Write(char[] buffer, int offset, int count);
void WriteLine(string text);
void toggleDTR();
// Properties
//Stream BaseStream { get; }
int BaudRate { get; set; }
//bool BreakState { get; set; }
int BytesToRead { get; }
int BytesToWrite { get; }
//bool CDHolding { get; }
//bool CtsHolding { get; }
int DataBits { get; set; }
//bool DiscardNull { get; set; }
//bool DsrHolding { get; }
bool DtrEnable { get; set; }
//Encoding Encoding { get; set; }
//Handshake Handshake { get; set; }
bool IsOpen { get; }
//string NewLine { get; set; }
Parity Parity { get; set; }
//byte ParityReplace { get; set; }
string PortName { get; set; }
int ReadBufferSize { get; set; }
int ReadTimeout { get; set; }
int ReceivedBytesThreshold { get; set; }
bool RtsEnable { get; set; }
StopBits StopBits { get; set; }
int WriteBufferSize { get; set; }
int WriteTimeout { get; set; }
}
}

View File

@ -1,85 +1,85 @@
using System;
using System.Collections.Generic;
using System.Text;
using System.IO.Ports;
using System.IO;
using System.Linq;
namespace ArdupilotMega
{
class SerialPort : System.IO.Ports.SerialPort,ICommsSerial
{
public new void Open()
{
if (base.IsOpen)
return;
base.Open();
}
public void toggleDTR()
{
bool open = this.IsOpen;
if (!open)
this.Open();
base.DtrEnable = false;
base.RtsEnable = false;
System.Threading.Thread.Sleep(50);
base.DtrEnable = true;
base.RtsEnable = true;
System.Threading.Thread.Sleep(50);
if (!open)
this.Close();
}
public new static string[] GetPortNames()
{
List<string> allPorts = new List<string>();
if (Directory.Exists("/dev/"))
{
if (Directory.Exists("/dev/serial/by-id/"))
allPorts.AddRange(Directory.GetFiles("/dev/serial/by-id/", "*"));
allPorts.AddRange(Directory.GetFiles("/dev/", "ttyACM*"));
allPorts.AddRange(Directory.GetFiles("/dev/", "ttyUSB*"));
}
string[] ports = System.IO.Ports.SerialPort.GetPortNames()
.Select(p => p.TrimEnd())
.Select(FixBlueToothPortNameBug)
.ToArray();
allPorts.AddRange(ports);
return allPorts.ToArray();
}
// .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 static 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;
}
}
}
using System;
using System.Collections.Generic;
using System.Text;
using System.IO.Ports;
using System.IO;
using System.Linq;
namespace ArdupilotMega.Comms
{
class SerialPort : System.IO.Ports.SerialPort,ICommsSerial
{
public new void Open()
{
if (base.IsOpen)
return;
base.Open();
}
public void toggleDTR()
{
bool open = this.IsOpen;
if (!open)
this.Open();
base.DtrEnable = false;
base.RtsEnable = false;
System.Threading.Thread.Sleep(50);
base.DtrEnable = true;
base.RtsEnable = true;
System.Threading.Thread.Sleep(50);
if (!open)
this.Close();
}
public new static string[] GetPortNames()
{
List<string> allPorts = new List<string>();
if (Directory.Exists("/dev/"))
{
if (Directory.Exists("/dev/serial/by-id/"))
allPorts.AddRange(Directory.GetFiles("/dev/serial/by-id/", "*"));
allPorts.AddRange(Directory.GetFiles("/dev/", "ttyACM*"));
allPorts.AddRange(Directory.GetFiles("/dev/", "ttyUSB*"));
}
string[] ports = System.IO.Ports.SerialPort.GetPortNames()
.Select(p => p.TrimEnd())
.Select(FixBlueToothPortNameBug)
.ToArray();
allPorts.AddRange(ports);
return allPorts.ToArray();
}
// .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 static 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;
}
}
}

View File

@ -9,9 +9,9 @@ using System.Net; // dns, ip address
using System.Net.Sockets; // tcplistner
using log4net;
namespace System.IO.Ports
namespace ArdupilotMega.Comms
{
public class TcpSerial : ArdupilotMega.ICommsSerial
public class TcpSerial : ArdupilotMega.Comms.ICommsSerial
{
private static readonly ILog log = LogManager.GetLogger(MethodBase.GetCurrentMethod().DeclaringType);
TcpClient client = new TcpClient();
@ -93,11 +93,11 @@ namespace System.IO.Ports
if (ArdupilotMega.MainV2.config["TCP_host"] != null)
host = ArdupilotMega.MainV2.config["TCP_host"].ToString();
if (Windows.Forms.DialogResult.Cancel == ArdupilotMega.Common.InputBox("remote host", "Enter host name/ip (ensure remote end is already started)", ref host))
if (System.Windows.Forms.DialogResult.Cancel == ArdupilotMega.Common.InputBox("remote host", "Enter host name/ip (ensure remote end is already started)", ref host))
{
throw new Exception("Canceled by request");
}
if (Windows.Forms.DialogResult.Cancel == ArdupilotMega.Common.InputBox("remote Port", "Enter remote port", ref dest))
if (System.Windows.Forms.DialogResult.Cancel == ArdupilotMega.Common.InputBox("remote Port", "Enter remote port", ref dest))
{
throw new Exception("Canceled by request");
}

View File

@ -1,301 +1,304 @@
using System.Reflection;
using System.Text;
using System.Net; // dns, ip address
using System.Net.Sockets; // tcplistner
using log4net;
using ArdupilotMega.Controls;
namespace System.IO.Ports
{
public class UdpSerial : ArdupilotMega.ICommsSerial
{
private static readonly ILog log = LogManager.GetLogger(MethodBase.GetCurrentMethod().DeclaringType);
UdpClient client = new UdpClient();
IPEndPoint RemoteIpEndPoint = new IPEndPoint(IPAddress.Any, 0);
byte[] rbuffer = new byte[0];
int rbufferread = 0;
public int WriteBufferSize { get; set; }
public int WriteTimeout { get; set; }
public int ReceivedBytesThreshold { get; set; }
public bool RtsEnable { get; set; }
~UdpSerial()
{
this.Close();
client = null;
}
public UdpSerial()
{
//System.Threading.Thread.CurrentThread.CurrentUICulture = new System.Globalization.CultureInfo("en-US");
//System.Threading.Thread.CurrentThread.CurrentCulture = new System.Globalization.CultureInfo("en-US");
Port = "14550";
}
public void toggleDTR()
{
}
public string Port { get; set; }
public int ReadTimeout
{
get;// { return client.ReceiveTimeout; }
set;// { client.ReceiveTimeout = value; }
}
public int ReadBufferSize {get;set;}
public int BaudRate { get; set; }
public StopBits StopBits { get; set; }
public Parity Parity { get; set; }
public int DataBits { get; set; }
public string PortName { get; set; }
public int BytesToRead
{
get { return client.Available + rbuffer.Length - rbufferread; }
}
public int BytesToWrite { get {return 0;} }
public bool IsOpen { get { if (client.Client == null) return false; return client.Client.Connected; } }
public bool DtrEnable
{
get;
set;
}
public void Open()
{
if (client.Client.Connected)
{
log.Info("udpserial socket already open");
return;
}
ProgressReporterDialogue frmProgressReporter = new ProgressReporterDialogue
{
StartPosition = System.Windows.Forms.FormStartPosition.CenterScreen,
Text = "Connecting Mavlink UDP"
};
frmProgressReporter.DoWork += frmProgressReporter_DoWork;
frmProgressReporter.UpdateProgressAndStatus(-1, "Connecting Mavlink UDP");
ArdupilotMega.ThemeManager.ApplyThemeTo(frmProgressReporter);
frmProgressReporter.RunBackgroundOperationAsync();
}
void frmProgressReporter_DoWork(object sender, ArdupilotMega.Controls.ProgressWorkerEventArgs e)
{
string dest = Port;
if (ArdupilotMega.MainV2.config["UDP_port"] != null)
dest = ArdupilotMega.MainV2.config["UDP_port"].ToString();
ArdupilotMega.Common.InputBox("Listern Port", "Enter Local port (ensure remote end is already sending)", ref dest);
Port = dest;
ArdupilotMega.MainV2.config["UDP_port"] = Port;
client = new UdpClient(int.Parse(Port));
while (true)
{
((ProgressReporterDialogue)sender).UpdateProgressAndStatus(-1, "Waiting for UDP");
System.Threading.Thread.Sleep(500);
if (((ProgressReporterDialogue)sender).doWorkArgs.CancelRequested)
{
((ProgressReporterDialogue)sender).doWorkArgs.CancelAcknowledged = true;
try
{
client.Close();
}
catch { }
return;
}
if (BytesToRead > 0)
break;
}
if (BytesToRead == 0)
return;
try
{
client.Receive(ref RemoteIpEndPoint);
log.InfoFormat("NetSerial connecting to {0} : {1}", RemoteIpEndPoint.Address, RemoteIpEndPoint.Port);
client.Connect(RemoteIpEndPoint);
}
catch (Exception ex)
{
if (client != null && client.Client.Connected)
{
client.Close();
}
log.Info(ex.ToString());
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);
}
}
void VerifyConnected()
{
if (client == null || !IsOpen)
{
throw new Exception("The socket/serialproxy is closed");
}
}
public int Read(byte[] readto,int offset,int length)
{
VerifyConnected();
try
{
if (length < 1) { return 0; }
if (rbufferread == rbuffer.Length)
{
MemoryStream r = new MemoryStream();
while (client.Available > 0)
{
Byte[] b = client.Receive(ref RemoteIpEndPoint);
r.Write(b, 0, b.Length);
}
rbuffer = r.ToArray();
rbufferread = 0;
}
Array.Copy(rbuffer, rbufferread, readto, offset, length);
rbufferread += length;
return length;
}
catch { throw new Exception("Socket Closed"); }
}
public int ReadByte()
{
VerifyConnected();
int count = 0;
while (this.BytesToRead == 0)
{
System.Threading.Thread.Sleep(1);
if (count > ReadTimeout)
throw new Exception("NetSerial Timeout on read");
count++;
}
byte[] buffer = new byte[1];
Read(buffer, 0, 1);
return buffer[0];
}
public int ReadChar()
{
return ReadByte();
}
public string ReadExisting()
{
VerifyConnected();
byte[] data = new byte[client.Available];
if (data.Length > 0)
Read(data, 0, data.Length);
string line = Encoding.ASCII.GetString(data, 0, data.Length);
return line;
}
public void WriteLine(string line)
{
VerifyConnected();
line = line + "\n";
Write(line);
}
public void Write(string line)
{
VerifyConnected();
byte[] data = new System.Text.ASCIIEncoding().GetBytes(line);
Write(data, 0, data.Length);
}
public void Write(byte[] write, int offset, int length)
{
VerifyConnected();
try
{
client.Send(write, length);
}
catch { }//throw new Exception("Comport / Socket Closed"); }
}
public void DiscardInBuffer()
{
VerifyConnected();
int size = client.Available;
byte[] crap = new byte[size];
log.InfoFormat("UdpSerial DiscardInBuffer {0}",size);
Read(crap, 0, size);
}
public string ReadLine() {
byte[] temp = new byte[4000];
int count = 0;
int timeout = 0;
while (timeout <= 100)
{
if (!this.IsOpen) { break; }
if (this.BytesToRead > 0)
{
byte letter = (byte)this.ReadByte();
temp[count] = letter;
if (letter == '\n') // normal line
{
break;
}
count++;
if (count == temp.Length)
break;
timeout = 0;
} else {
timeout++;
System.Threading.Thread.Sleep(5);
}
}
Array.Resize<byte>(ref temp, count + 1);
return Encoding.ASCII.GetString(temp, 0, temp.Length);
}
public void Close()
{
if (client.Client != null && client.Client.Connected)
{
client.Client.Close();
client.Close();
}
client = new UdpClient();
}
}
}
using System.Reflection;
using System.Text;
using System.Net; // dns, ip address
using System.Net.Sockets; // tcplistner
using log4net;
using ArdupilotMega.Controls;
using System.IO.Ports;
using System.IO;
using System;
namespace ArdupilotMega.Comms
{
public class UdpSerial : ArdupilotMega.Comms.ICommsSerial
{
private static readonly ILog log = LogManager.GetLogger(MethodBase.GetCurrentMethod().DeclaringType);
UdpClient client = new UdpClient();
IPEndPoint RemoteIpEndPoint = new IPEndPoint(IPAddress.Any, 0);
byte[] rbuffer = new byte[0];
int rbufferread = 0;
public int WriteBufferSize { get; set; }
public int WriteTimeout { get; set; }
public int ReceivedBytesThreshold { get; set; }
public bool RtsEnable { get; set; }
~UdpSerial()
{
this.Close();
client = null;
}
public UdpSerial()
{
//System.Threading.Thread.CurrentThread.CurrentUICulture = new System.Globalization.CultureInfo("en-US");
//System.Threading.Thread.CurrentThread.CurrentCulture = new System.Globalization.CultureInfo("en-US");
Port = "14550";
}
public void toggleDTR()
{
}
public string Port { get; set; }
public int ReadTimeout
{
get;// { return client.ReceiveTimeout; }
set;// { client.ReceiveTimeout = value; }
}
public int ReadBufferSize {get;set;}
public int BaudRate { get; set; }
public StopBits StopBits { get; set; }
public Parity Parity { get; set; }
public int DataBits { get; set; }
public string PortName { get; set; }
public int BytesToRead
{
get { return client.Available + rbuffer.Length - rbufferread; }
}
public int BytesToWrite { get {return 0;} }
public bool IsOpen { get { if (client.Client == null) return false; return client.Client.Connected; } }
public bool DtrEnable
{
get;
set;
}
public void Open()
{
if (client.Client.Connected)
{
log.Info("udpserial socket already open");
return;
}
ProgressReporterDialogue frmProgressReporter = new ProgressReporterDialogue
{
StartPosition = System.Windows.Forms.FormStartPosition.CenterScreen,
Text = "Connecting Mavlink UDP"
};
frmProgressReporter.DoWork += frmProgressReporter_DoWork;
frmProgressReporter.UpdateProgressAndStatus(-1, "Connecting Mavlink UDP");
ArdupilotMega.ThemeManager.ApplyThemeTo(frmProgressReporter);
frmProgressReporter.RunBackgroundOperationAsync();
}
void frmProgressReporter_DoWork(object sender, ArdupilotMega.Controls.ProgressWorkerEventArgs e)
{
string dest = Port;
if (ArdupilotMega.MainV2.config["UDP_port"] != null)
dest = ArdupilotMega.MainV2.config["UDP_port"].ToString();
ArdupilotMega.Common.InputBox("Listern Port", "Enter Local port (ensure remote end is already sending)", ref dest);
Port = dest;
ArdupilotMega.MainV2.config["UDP_port"] = Port;
client = new UdpClient(int.Parse(Port));
while (true)
{
((ProgressReporterDialogue)sender).UpdateProgressAndStatus(-1, "Waiting for UDP");
System.Threading.Thread.Sleep(500);
if (((ProgressReporterDialogue)sender).doWorkArgs.CancelRequested)
{
((ProgressReporterDialogue)sender).doWorkArgs.CancelAcknowledged = true;
try
{
client.Close();
}
catch { }
return;
}
if (BytesToRead > 0)
break;
}
if (BytesToRead == 0)
return;
try
{
client.Receive(ref RemoteIpEndPoint);
log.InfoFormat("NetSerial connecting to {0} : {1}", RemoteIpEndPoint.Address, RemoteIpEndPoint.Port);
client.Connect(RemoteIpEndPoint);
}
catch (Exception ex)
{
if (client != null && client.Client.Connected)
{
client.Close();
}
log.Info(ex.ToString());
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);
}
}
void VerifyConnected()
{
if (client == null || !IsOpen)
{
throw new Exception("The socket/serialproxy is closed");
}
}
public int Read(byte[] readto,int offset,int length)
{
VerifyConnected();
try
{
if (length < 1) { return 0; }
if (rbufferread == rbuffer.Length)
{
MemoryStream r = new MemoryStream();
while (client.Available > 0)
{
Byte[] b = client.Receive(ref RemoteIpEndPoint);
r.Write(b, 0, b.Length);
}
rbuffer = r.ToArray();
rbufferread = 0;
}
Array.Copy(rbuffer, rbufferread, readto, offset, length);
rbufferread += length;
return length;
}
catch { throw new Exception("Socket Closed"); }
}
public int ReadByte()
{
VerifyConnected();
int count = 0;
while (this.BytesToRead == 0)
{
System.Threading.Thread.Sleep(1);
if (count > ReadTimeout)
throw new Exception("NetSerial Timeout on read");
count++;
}
byte[] buffer = new byte[1];
Read(buffer, 0, 1);
return buffer[0];
}
public int ReadChar()
{
return ReadByte();
}
public string ReadExisting()
{
VerifyConnected();
byte[] data = new byte[client.Available];
if (data.Length > 0)
Read(data, 0, data.Length);
string line = Encoding.ASCII.GetString(data, 0, data.Length);
return line;
}
public void WriteLine(string line)
{
VerifyConnected();
line = line + "\n";
Write(line);
}
public void Write(string line)
{
VerifyConnected();
byte[] data = new System.Text.ASCIIEncoding().GetBytes(line);
Write(data, 0, data.Length);
}
public void Write(byte[] write, int offset, int length)
{
VerifyConnected();
try
{
client.Send(write, length);
}
catch { }//throw new Exception("Comport / Socket Closed"); }
}
public void DiscardInBuffer()
{
VerifyConnected();
int size = client.Available;
byte[] crap = new byte[size];
log.InfoFormat("UdpSerial DiscardInBuffer {0}",size);
Read(crap, 0, size);
}
public string ReadLine() {
byte[] temp = new byte[4000];
int count = 0;
int timeout = 0;
while (timeout <= 100)
{
if (!this.IsOpen) { break; }
if (this.BytesToRead > 0)
{
byte letter = (byte)this.ReadByte();
temp[count] = letter;
if (letter == '\n') // normal line
{
break;
}
count++;
if (count == temp.Length)
break;
timeout = 0;
} else {
timeout++;
System.Threading.Thread.Sleep(5);
}
}
Array.Resize<byte>(ref temp, count + 1);
return Encoding.ASCII.GetString(temp, 0, temp.Length);
}
public void Close()
{
if (client.Client != null && client.Client.Connected)
{
client.Client.Close();
client.Close();
}
client = new UdpClient();
}
}
}

View File

@ -118,7 +118,7 @@ namespace ArdupilotMega.Controls
this.Controls.Add(lbl);
MyButton but = new MyButton();
ArdupilotMega.Controls.MyButton but = new ArdupilotMega.Controls.MyButton();
but.Text = "Save";
but.Location = new Point(optionx + 100, y);

View File

@ -169,7 +169,7 @@ namespace System.Windows.Forms
switch (buttons)
{
case MessageBoxButtons.OK:
var but = new MyButton
var but = new ArdupilotMega.Controls.MyButton
{
Size = new Size(75, 23),
Text = "OK",
@ -187,7 +187,7 @@ namespace System.Windows.Forms
if (msgBoxFrm.Width < (75 * 2 + FORM_X_MARGIN * 3))
msgBoxFrm.Width = (75 * 2 + FORM_X_MARGIN * 3);
var butyes = new MyButton
var butyes = new ArdupilotMega.Controls.MyButton
{
Size = new Size(75, 23),
Text = "Yes",
@ -199,7 +199,7 @@ namespace System.Windows.Forms
msgBoxFrm.Controls.Add(butyes);
msgBoxFrm.AcceptButton = butyes;
var butno = new MyButton
var butno = new ArdupilotMega.Controls.MyButton
{
Size = new Size(75, 23),
Text = "No",

View File

@ -1,4 +1,4 @@
namespace ArdupilotMega
namespace ArdupilotMega.Controls
{
partial class ImageLabel
{

View File

@ -7,7 +7,7 @@ using System.Linq;
using System.Text;
using System.Windows.Forms;
namespace ArdupilotMega
namespace ArdupilotMega.Controls
{
public partial class ImageLabel : UserControl //ContainerControl
{

View File

@ -7,46 +7,45 @@ using System.Linq;
using System.Text;
using System.Windows.Forms;
public partial class LineSeparator : UserControl
namespace ArdupilotMega.Controls
{
public LineSeparator()
public partial class LineSeparator : UserControl
{
this.Height = 2;
public LineSeparator()
{
this.Height = 2;
this.Paint += new PaintEventHandler(LineSeparator_Paint);
this.Paint += new PaintEventHandler(LineSeparator_Paint);
this.MaximumSize = new Size(2000, 2);
this.MaximumSize = new Size(2000, 2);
this.MinimumSize = new Size(0, 2);
this.MinimumSize = new Size(0, 2);
//this.Width = 350;
//this.Width = 350;
}
private void LineSeparator_Paint(object sender, PaintEventArgs e)
{
Graphics g = e.Graphics;
g.DrawLine(
Pens.DarkGray, new Point(0, 0), new Point(this.Width, 0));
g.DrawLine(
Pens.White, new Point(0, 1), new Point(this.Width, 1));
}
}
private void LineSeparator_Paint(object sender, PaintEventArgs e)
{
Graphics g = e.Graphics;
g.DrawLine(
Pens.DarkGray, new Point(0, 0), new Point(this.Width, 0));
g.DrawLine(
Pens.White, new Point(0, 1), new Point(this.Width, 1));
}
}
}

View File

@ -10,7 +10,7 @@ using System.Windows.Forms;
using System.Drawing.Drawing2D;
namespace ArdupilotMega
namespace ArdupilotMega.Controls
{
class MyButton : Button
{

View File

@ -7,10 +7,10 @@ using System.Linq;
using System.Text;
using System.Windows.Forms;
namespace ArdupilotMega
namespace ArdupilotMega.Controls
{
/// <summary>
/// profiling showed that the built in Label function was using alot ot call time.
/// profiling showed that the built in Label function was using alot of call time.
/// </summary>
public partial class MyLabel : Control //: Label
{

View File

@ -4,7 +4,7 @@ using System.Linq;
using System.Text;
using System.Windows.Forms;
namespace ArdupilotMega
namespace ArdupilotMega.Controls
{
class MyTrackBar : TrackBar
{

View File

@ -5,6 +5,9 @@ using System.Text;
namespace System.Windows.Forms
{
/// <summary>
/// This is a mono fix, windows handles this error, mono crashs
/// </summary>
public class MyUserControl : System.Windows.Forms.UserControl
{
protected override void WndProc(ref Message m)

View File

@ -5,8 +5,6 @@ using System.Windows.Forms;
namespace ArdupilotMega.Controls
{
/// <summary>
/// Form that is shown to the user during a background operation
/// </summary>

View File

@ -1,112 +0,0 @@
namespace ArdupilotMega
{
partial class XorPlus
{
/// <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 Component 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.label16 = new System.Windows.Forms.Label();
this.label15 = new System.Windows.Forms.Label();
this.pictureBoxQuadX = new System.Windows.Forms.PictureBox();
this.pictureBoxQuad = new System.Windows.Forms.PictureBox();
((System.ComponentModel.ISupportInitialize)(this.pictureBoxQuadX)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.pictureBoxQuad)).BeginInit();
this.SuspendLayout();
//
// label16
//
this.label16.AutoSize = true;
this.label16.ImeMode = System.Windows.Forms.ImeMode.NoControl;
this.label16.Location = new System.Drawing.Point(108, 211);
this.label16.Name = "label16";
this.label16.Size = new System.Drawing.Size(192, 26);
this.label16.TabIndex = 11;
this.label16.Text = "NOTE: images are for presentation only\r\nwill work with hexa\'s etc";
//
// label15
//
this.label15.AutoSize = true;
this.label15.ImeMode = System.Windows.Forms.ImeMode.NoControl;
this.label15.Location = new System.Drawing.Point(151, 2);
this.label15.Name = "label15";
this.label15.Size = new System.Drawing.Size(102, 13);
this.label15.TabIndex = 10;
this.label15.Text = "Frame Setup (+ or x)";
//
// pictureBoxQuadX
//
this.pictureBoxQuadX.Cursor = System.Windows.Forms.Cursors.Hand;
this.pictureBoxQuadX.Image = global::ArdupilotMega.Properties.Resources.quadx;
this.pictureBoxQuadX.ImeMode = System.Windows.Forms.ImeMode.NoControl;
this.pictureBoxQuadX.Location = new System.Drawing.Point(210, 18);
this.pictureBoxQuadX.Name = "pictureBoxQuadX";
this.pictureBoxQuadX.Size = new System.Drawing.Size(190, 190);
this.pictureBoxQuadX.SizeMode = System.Windows.Forms.PictureBoxSizeMode.Zoom;
this.pictureBoxQuadX.TabIndex = 9;
this.pictureBoxQuadX.TabStop = false;
this.pictureBoxQuadX.Click += new System.EventHandler(this.pictureBoxQuadX_Click);
//
// pictureBoxQuad
//
this.pictureBoxQuad.Cursor = System.Windows.Forms.Cursors.Hand;
this.pictureBoxQuad.Image = global::ArdupilotMega.Properties.Resources.quad;
this.pictureBoxQuad.ImeMode = System.Windows.Forms.ImeMode.NoControl;
this.pictureBoxQuad.Location = new System.Drawing.Point(3, 18);
this.pictureBoxQuad.Name = "pictureBoxQuad";
this.pictureBoxQuad.Size = new System.Drawing.Size(190, 190);
this.pictureBoxQuad.SizeMode = System.Windows.Forms.PictureBoxSizeMode.Zoom;
this.pictureBoxQuad.TabIndex = 8;
this.pictureBoxQuad.TabStop = false;
this.pictureBoxQuad.Click += new System.EventHandler(this.pictureBoxQuad_Click);
//
// XorPlus
//
this.AutoScaleDimensions = new System.Drawing.SizeF(6F, 13F);
this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font;
this.ClientSize = new System.Drawing.Size(404, 242);
this.Controls.Add(this.label16);
this.Controls.Add(this.label15);
this.Controls.Add(this.pictureBoxQuadX);
this.Controls.Add(this.pictureBoxQuad);
this.FormBorderStyle = System.Windows.Forms.FormBorderStyle.FixedToolWindow;
this.Name = "XorPlus";
this.StartPosition = System.Windows.Forms.FormStartPosition.CenterParent;
this.Text = "Frame Type";
((System.ComponentModel.ISupportInitialize)(this.pictureBoxQuadX)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.pictureBoxQuad)).EndInit();
this.ResumeLayout(false);
this.PerformLayout();
}
#endregion
private System.Windows.Forms.Label label16;
private System.Windows.Forms.Label label15;
private System.Windows.Forms.PictureBox pictureBoxQuadX;
private System.Windows.Forms.PictureBox pictureBoxQuad;
}
}

View File

@ -1,48 +0,0 @@
using System;
using System.Collections.Generic;
using System.ComponentModel;
using System.Drawing;
using System.Data;
using System.Linq;
using System.Text;
using System.Windows.Forms;
namespace ArdupilotMega
{
public partial class XorPlus : Form
{
public new event EventHandler Click;
/// <summary>
/// either X or +
/// </summary>
public string frame = "";
public XorPlus()
{
InitializeComponent();
}
private void pictureBoxQuad_Click(object sender, EventArgs e)
{
frame = "+";
if (Click != null)
{
Click(sender, new EventArgs());
}
this.Close();
}
private void pictureBoxQuadX_Click(object sender, EventArgs e)
{
frame = "X";
if (Click != null)
{
Click(sender, new EventArgs());
}
this.Close();
}
}
}

View File

@ -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>

View File

@ -3,8 +3,11 @@ using System.Collections.Generic;
using System.Linq;
using System.Text;
namespace ArdupilotMega
namespace ArdupilotMega.Controls
{
/// <summary>
/// Mono handles calls from other thread difrently - this prevents those crashs
/// </summary>
class myGMAP : GMap.NET.WindowsForms.GMapControl
{
public bool inOnPaint = false;

View File

@ -141,13 +141,13 @@
this.RLL2SRV_P = new System.Windows.Forms.NumericUpDown();
this.label52 = new System.Windows.Forms.Label();
this.TabAC = new System.Windows.Forms.TabPage();
this.myLabel4 = new ArdupilotMega.MyLabel();
this.myLabel3 = new ArdupilotMega.MyLabel();
this.myLabel4 = new ArdupilotMega.Controls.MyLabel();
this.myLabel3 = new ArdupilotMega.Controls.MyLabel();
this.TUNE_LOW = new System.Windows.Forms.NumericUpDown();
this.TUNE_HIGH = new System.Windows.Forms.NumericUpDown();
this.myLabel2 = new ArdupilotMega.MyLabel();
this.myLabel2 = new ArdupilotMega.Controls.MyLabel();
this.TUNE = new System.Windows.Forms.ComboBox();
this.myLabel1 = new ArdupilotMega.MyLabel();
this.myLabel1 = new ArdupilotMega.Controls.MyLabel();
this.CH7_OPT = new System.Windows.Forms.ComboBox();
this.groupBox5 = new System.Windows.Forms.GroupBox();
this.THR_RATE_D = new System.Windows.Forms.NumericUpDown();
@ -276,17 +276,17 @@
this.CHK_hudshow = new System.Windows.Forms.CheckBox();
this.label92 = new System.Windows.Forms.Label();
this.CMB_videosources = new System.Windows.Forms.ComboBox();
this.BUT_Joystick = new ArdupilotMega.MyButton();
this.BUT_videostop = new ArdupilotMega.MyButton();
this.BUT_videostart = new ArdupilotMega.MyButton();
this.BUT_Joystick = new ArdupilotMega.Controls.MyButton();
this.BUT_videostop = new ArdupilotMega.Controls.MyButton();
this.BUT_videostart = new ArdupilotMega.Controls.MyButton();
this.TabSetup = new System.Windows.Forms.TabPage();
this.label109 = new System.Windows.Forms.Label();
this.BUT_rerequestparams = new ArdupilotMega.MyButton();
this.BUT_writePIDS = new ArdupilotMega.MyButton();
this.BUT_save = new ArdupilotMega.MyButton();
this.BUT_load = new ArdupilotMega.MyButton();
this.BUT_rerequestparams = new ArdupilotMega.Controls.MyButton();
this.BUT_writePIDS = new ArdupilotMega.Controls.MyButton();
this.BUT_save = new ArdupilotMega.Controls.MyButton();
this.BUT_load = new ArdupilotMega.Controls.MyButton();
this.toolTip1 = new System.Windows.Forms.ToolTip(this.components);
this.BUT_compare = new ArdupilotMega.MyButton();
this.BUT_compare = new ArdupilotMega.Controls.MyButton();
this.groupBox17 = new System.Windows.Forms.GroupBox();
this.LOITER_LAT_D = new System.Windows.Forms.NumericUpDown();
this.label28 = new System.Windows.Forms.Label();
@ -2333,10 +2333,10 @@
#endregion
private MyButton BUT_save;
private MyButton BUT_load;
private ArdupilotMega.Controls.MyButton BUT_save;
private ArdupilotMega.Controls.MyButton BUT_load;
private System.Windows.Forms.DataGridView Params;
private MyButton BUT_writePIDS;
private ArdupilotMega.Controls.MyButton BUT_writePIDS;
private System.Windows.Forms.TabControl ConfigTabs;
private System.Windows.Forms.TabPage TabAP;
private System.Windows.Forms.TabPage TabAC;
@ -2505,8 +2505,8 @@
private System.Windows.Forms.TabPage TabPlanner;
private System.Windows.Forms.Label label92;
private System.Windows.Forms.ComboBox CMB_videosources;
private MyButton BUT_videostop;
private MyButton BUT_videostart;
private ArdupilotMega.Controls.MyButton BUT_videostop;
private ArdupilotMega.Controls.MyButton BUT_videostart;
private System.Windows.Forms.CheckBox CHK_hudshow;
private System.Windows.Forms.CheckBox CHK_enablespeech;
private System.Windows.Forms.ComboBox CMB_language;
@ -2516,9 +2516,9 @@
private System.Windows.Forms.CheckBox CHK_speechwaypoint;
private System.Windows.Forms.CheckBox CHK_speechmode;
private System.Windows.Forms.CheckBox CHK_speechcustom;
private MyButton BUT_rerequestparams;
private ArdupilotMega.Controls.MyButton BUT_rerequestparams;
private System.Windows.Forms.CheckBox CHK_speechbattery;
private MyButton BUT_Joystick;
private ArdupilotMega.Controls.MyButton BUT_Joystick;
private System.Windows.Forms.Label label96;
private System.Windows.Forms.Label label95;
private System.Windows.Forms.ComboBox CMB_speedunits;
@ -2553,7 +2553,7 @@
private System.Windows.Forms.DataGridViewTextBoxColumn Default;
private System.Windows.Forms.DataGridViewTextBoxColumn mavScale;
private System.Windows.Forms.DataGridViewTextBoxColumn RawValue;
private MyButton BUT_compare;
private ArdupilotMega.Controls.MyButton BUT_compare;
private System.Windows.Forms.Label label12;
private System.Windows.Forms.CheckBox CHK_GDIPlus;
private System.Windows.Forms.GroupBox groupBox5;
@ -2566,9 +2566,9 @@
private System.Windows.Forms.Label label109;
private System.Windows.Forms.Label label14;
private System.Windows.Forms.Label label26;
private MyLabel myLabel1;
private ArdupilotMega.Controls.MyLabel myLabel1;
private System.Windows.Forms.ComboBox CH7_OPT;
private MyLabel myLabel2;
private ArdupilotMega.Controls.MyLabel myLabel2;
private System.Windows.Forms.ComboBox TUNE;
private System.Windows.Forms.NumericUpDown RATE_YAW_D;
private System.Windows.Forms.Label label10;
@ -2586,8 +2586,8 @@
private System.Windows.Forms.NumericUpDown TUNE_HIGH;
private System.Windows.Forms.Label label33;
private System.Windows.Forms.ComboBox CMB_ratesensors;
private MyLabel myLabel4;
private MyLabel myLabel3;
private ArdupilotMega.Controls.MyLabel myLabel4;
private ArdupilotMega.Controls.MyLabel myLabel3;
private System.Windows.Forms.GroupBox groupBox17;
private System.Windows.Forms.NumericUpDown LOITER_LAT_D;
private System.Windows.Forms.Label label28;

View File

@ -13,6 +13,7 @@ using System.Globalization;
using System.Threading;
using DirectShowLib;
using System.Runtime.InteropServices;
using ArdupilotMega.Controls;
namespace ArdupilotMega.GCSViews
{

View File

@ -367,7 +367,7 @@
<value>myLabel2</value>
</data>
<data name="&gt;&gt;myLabel2.Type" xml:space="preserve">
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null</value>
<value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;myLabel2.Parent" xml:space="preserve">
<value>groupBox17</value>
@ -379,7 +379,7 @@
<value>myLabel4</value>
</data>
<data name="&gt;&gt;myLabel4.Type" xml:space="preserve">
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null</value>
<value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;myLabel4.Parent" xml:space="preserve">
<value>groupBox17</value>
@ -403,7 +403,7 @@
<value>myLabel3</value>
</data>
<data name="&gt;&gt;myLabel3.Type" xml:space="preserve">
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null</value>
<value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;myLabel3.Parent" xml:space="preserve">
<value>groupBox17</value>
@ -415,7 +415,7 @@
<value>myLabel1</value>
</data>
<data name="&gt;&gt;myLabel1.Type" xml:space="preserve">
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null</value>
<value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;myLabel1.Parent" xml:space="preserve">
<value>groupBox17</value>
@ -2341,7 +2341,7 @@
<value>BUT_Joystick</value>
</data>
<data name="&gt;&gt;BUT_Joystick.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null</value>
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;BUT_Joystick.Parent" xml:space="preserve">
<value>TabPlanner</value>
@ -2353,7 +2353,7 @@
<value>BUT_videostop</value>
</data>
<data name="&gt;&gt;BUT_videostop.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null</value>
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;BUT_videostop.Parent" xml:space="preserve">
<value>TabPlanner</value>
@ -2365,7 +2365,7 @@
<value>BUT_videostart</value>
</data>
<data name="&gt;&gt;BUT_videostart.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null</value>
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;BUT_videostart.Parent" xml:space="preserve">
<value>TabPlanner</value>
@ -5926,7 +5926,7 @@
<value>myLabel4</value>
</data>
<data name="&gt;&gt;myLabel4.Type" xml:space="preserve">
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null</value>
<value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;myLabel4.Parent" xml:space="preserve">
<value>groupBox17</value>
@ -5950,7 +5950,7 @@
<value>myLabel3</value>
</data>
<data name="&gt;&gt;myLabel3.Type" xml:space="preserve">
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null</value>
<value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;myLabel3.Parent" xml:space="preserve">
<value>groupBox17</value>
@ -6016,7 +6016,7 @@
<value>myLabel2</value>
</data>
<data name="&gt;&gt;myLabel2.Type" xml:space="preserve">
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null</value>
<value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;myLabel2.Parent" xml:space="preserve">
<value>groupBox17</value>
@ -6127,7 +6127,7 @@
<value>myLabel1</value>
</data>
<data name="&gt;&gt;myLabel1.Type" xml:space="preserve">
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null</value>
<value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;myLabel1.Parent" xml:space="preserve">
<value>groupBox17</value>
@ -9018,7 +9018,7 @@ GDI+ = Enabled</value>
<value>BUT_Joystick</value>
</data>
<data name="&gt;&gt;BUT_Joystick.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null</value>
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;BUT_Joystick.Parent" xml:space="preserve">
<value>TabPlanner</value>
@ -9045,7 +9045,7 @@ GDI+ = Enabled</value>
<value>BUT_videostop</value>
</data>
<data name="&gt;&gt;BUT_videostop.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null</value>
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;BUT_videostop.Parent" xml:space="preserve">
<value>TabPlanner</value>
@ -9072,7 +9072,7 @@ GDI+ = Enabled</value>
<value>BUT_videostart</value>
</data>
<data name="&gt;&gt;BUT_videostart.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null</value>
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;BUT_videostart.Parent" xml:space="preserve">
<value>TabPlanner</value>
@ -9120,7 +9120,7 @@ GDI+ = Enabled</value>
<value>BUT_rerequestparams</value>
</data>
<data name="&gt;&gt;BUT_rerequestparams.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null</value>
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;BUT_rerequestparams.Parent" xml:space="preserve">
<value>$this</value>
@ -9153,7 +9153,7 @@ GDI+ = Enabled</value>
<value>BUT_writePIDS</value>
</data>
<data name="&gt;&gt;BUT_writePIDS.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null</value>
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;BUT_writePIDS.Parent" xml:space="preserve">
<value>$this</value>
@ -9189,7 +9189,7 @@ GDI+ = Enabled</value>
<value>BUT_save</value>
</data>
<data name="&gt;&gt;BUT_save.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null</value>
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;BUT_save.Parent" xml:space="preserve">
<value>$this</value>
@ -9225,7 +9225,7 @@ GDI+ = Enabled</value>
<value>BUT_load</value>
</data>
<data name="&gt;&gt;BUT_load.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null</value>
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;BUT_load.Parent" xml:space="preserve">
<value>$this</value>
@ -9258,7 +9258,7 @@ GDI+ = Enabled</value>
<value>BUT_compare</value>
</data>
<data name="&gt;&gt;BUT_compare.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null</value>
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4484.12593, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;BUT_compare.Parent" xml:space="preserve">
<value>$this</value>

View File

@ -31,7 +31,7 @@
this.components = new System.ComponentModel.Container();
System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(ConfigAccelerometerCalibrationPlane));
this.label28 = new System.Windows.Forms.Label();
this.BUT_levelplane = new ArdupilotMega.MyButton();
this.BUT_levelplane = new ArdupilotMega.Controls.MyButton();
this.CHK_manuallevel = new System.Windows.Forms.CheckBox();
this.toolTip1 = new System.Windows.Forms.ToolTip(this.components);
this.label1 = new System.Windows.Forms.Label();
@ -88,7 +88,7 @@
#endregion
private System.Windows.Forms.Label label28;
private MyButton BUT_levelplane;
private ArdupilotMega.Controls.MyButton BUT_levelplane;
private System.Windows.Forms.CheckBox CHK_manuallevel;
private System.Windows.Forms.ToolTip toolTip1;
private System.Windows.Forms.Label label1;

View File

@ -7,6 +7,7 @@ using System.Linq;
using System.Text;
using System.Windows.Forms;
using ArdupilotMega.Controls.BackstageView;
using ArdupilotMega.Controls;
namespace ArdupilotMega.GCSViews.ConfigurationView
{

View File

@ -175,7 +175,7 @@
<value>BUT_levelplane</value>
</data>
<data name="&gt;&gt;BUT_levelplane.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4492.39671, Culture=neutral, PublicKeyToken=null</value>
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4492.39671, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;BUT_levelplane.Parent" xml:space="preserve">
<value>$this</value>

View File

@ -33,7 +33,7 @@
this.label15 = new System.Windows.Forms.Label();
this.pictureBoxQuadX = new System.Windows.Forms.PictureBox();
this.pictureBoxQuad = new System.Windows.Forms.PictureBox();
this.BUT_levelac2 = new ArdupilotMega.MyButton();
this.BUT_levelac2 = new ArdupilotMega.Controls.MyButton();
this.pictureBox1 = new System.Windows.Forms.PictureBox();
this.pictureBox2 = new System.Windows.Forms.PictureBox();
this.pictureBox3 = new System.Windows.Forms.PictureBox();
@ -149,7 +149,7 @@
private System.Windows.Forms.Label label15;
private System.Windows.Forms.PictureBox pictureBoxQuadX;
private System.Windows.Forms.PictureBox pictureBoxQuad;
private MyButton BUT_levelac2;
private ArdupilotMega.Controls.MyButton BUT_levelac2;
private System.Windows.Forms.PictureBox pictureBox1;
private System.Windows.Forms.PictureBox pictureBox2;
private System.Windows.Forms.PictureBox pictureBox3;

View File

@ -7,6 +7,7 @@ using System.Linq;
using System.Text;
using System.Windows.Forms;
using ArdupilotMega.Controls.BackstageView;
using ArdupilotMega.Controls;
namespace ArdupilotMega.GCSViews.ConfigurationView
{

View File

@ -250,7 +250,7 @@
<value>BUT_levelac2</value>
</data>
<data name="&gt;&gt;BUT_levelac2.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4496.35237, Culture=neutral, PublicKeyToken=null</value>
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4496.35237, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;BUT_levelac2.Parent" xml:space="preserve">
<value>$this</value>

View File

@ -30,12 +30,12 @@
{
this.components = new System.ComponentModel.Container();
System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(ConfigArducopter));
this.myLabel3 = new ArdupilotMega.MyLabel();
this.myLabel3 = new ArdupilotMega.Controls.MyLabel();
this.TUNE_LOW = new System.Windows.Forms.NumericUpDown();
this.TUNE_HIGH = new System.Windows.Forms.NumericUpDown();
this.myLabel2 = new ArdupilotMega.MyLabel();
this.myLabel2 = new ArdupilotMega.Controls.MyLabel();
this.TUNE = new System.Windows.Forms.ComboBox();
this.myLabel1 = new ArdupilotMega.MyLabel();
this.myLabel1 = new ArdupilotMega.Controls.MyLabel();
this.CH7_OPT = new System.Windows.Forms.ComboBox();
this.groupBox5 = new System.Windows.Forms.GroupBox();
this.THR_RATE_D = new System.Windows.Forms.NumericUpDown();
@ -868,12 +868,12 @@
#endregion
private MyLabel myLabel3;
private ArdupilotMega.Controls.MyLabel myLabel3;
private System.Windows.Forms.NumericUpDown TUNE_LOW;
private System.Windows.Forms.NumericUpDown TUNE_HIGH;
private MyLabel myLabel2;
private ArdupilotMega.Controls.MyLabel myLabel2;
private System.Windows.Forms.ComboBox TUNE;
private MyLabel myLabel1;
private ArdupilotMega.Controls.MyLabel myLabel1;
private System.Windows.Forms.ComboBox CH7_OPT;
private System.Windows.Forms.GroupBox groupBox5;
private System.Windows.Forms.NumericUpDown THR_RATE_D;

View File

@ -8,6 +8,7 @@ using System.Text;
using System.Windows.Forms;
using ArdupilotMega.Controls.BackstageView;
using System.Collections;
using ArdupilotMega.Controls;
namespace ArdupilotMega.GCSViews.ConfigurationView
{

View File

@ -135,7 +135,7 @@
<value>myLabel3</value>
</data>
<data name="&gt;&gt;myLabel3.Type" xml:space="preserve">
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null</value>
<value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;myLabel3.Parent" xml:space="preserve">
<value>$this</value>
@ -201,7 +201,7 @@
<value>myLabel2</value>
</data>
<data name="&gt;&gt;myLabel2.Type" xml:space="preserve">
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null</value>
<value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;myLabel2.Parent" xml:space="preserve">
<value>$this</value>
@ -312,7 +312,7 @@
<value>myLabel1</value>
</data>
<data name="&gt;&gt;myLabel1.Type" xml:space="preserve">
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null</value>
<value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;myLabel1.Parent" xml:space="preserve">
<value>$this</value>

View File

@ -8,6 +8,7 @@ using System.Text;
using System.Windows.Forms;
using ArdupilotMega.Controls.BackstageView;
using System.Collections;
using ArdupilotMega.Controls;
namespace ArdupilotMega.GCSViews.ConfigurationView
{

View File

@ -7,6 +7,7 @@ using System.Linq;
using System.Text;
using System.Windows.Forms;
using ArdupilotMega.Controls.BackstageView;
using ArdupilotMega.Controls;
namespace ArdupilotMega.GCSViews.ConfigurationView
{

View File

@ -59,7 +59,7 @@
this.CMB_fmode2 = new System.Windows.Forms.ComboBox();
this.label1 = new System.Windows.Forms.Label();
this.CMB_fmode1 = new System.Windows.Forms.ComboBox();
this.BUT_SaveModes = new ArdupilotMega.MyButton();
this.BUT_SaveModes = new ArdupilotMega.Controls.MyButton();
((System.ComponentModel.ISupportInitialize)(this.currentStateBindingSource)).BeginInit();
this.SuspendLayout();
//
@ -312,7 +312,7 @@
private System.Windows.Forms.ComboBox CMB_fmode2;
private System.Windows.Forms.Label label1;
private System.Windows.Forms.ComboBox CMB_fmode1;
private MyButton BUT_SaveModes;
private ArdupilotMega.Controls.MyButton BUT_SaveModes;
private System.Windows.Forms.BindingSource currentStateBindingSource;
}
}

View File

@ -8,6 +8,7 @@ using System.Text;
using System.Windows.Forms;
using ArdupilotMega.Controls.BackstageView;
using ArdupilotMega.Utilities;
using ArdupilotMega.Controls;
namespace ArdupilotMega.GCSViews.ConfigurationView
{

View File

@ -946,7 +946,7 @@
<value>BUT_SaveModes</value>
</data>
<data name="&gt;&gt;BUT_SaveModes.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value>
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;BUT_SaveModes.Parent" xml:space="preserve">
<value>$this</value>

View File

@ -29,7 +29,7 @@
private void InitializeComponent()
{
System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(ConfigHardwareOptions));
this.BUT_MagCalibrationLive = new ArdupilotMega.MyButton();
this.BUT_MagCalibrationLive = new ArdupilotMega.Controls.MyButton();
this.label27 = new System.Windows.Forms.Label();
this.CMB_sonartype = new System.Windows.Forms.ComboBox();
this.CHK_enableoptflow = new System.Windows.Forms.CheckBox();
@ -43,7 +43,7 @@
this.pictureBox4 = new System.Windows.Forms.PictureBox();
this.pictureBox3 = new System.Windows.Forms.PictureBox();
this.pictureBox1 = new System.Windows.Forms.PictureBox();
this.BUT_MagCalibrationLog = new ArdupilotMega.MyButton();
this.BUT_MagCalibrationLog = new ArdupilotMega.Controls.MyButton();
this.CHK_autodec = new System.Windows.Forms.CheckBox();
((System.ComponentModel.ISupportInitialize)(this.pictureBox2)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.pictureBox4)).BeginInit();
@ -202,7 +202,7 @@
#endregion
private MyButton BUT_MagCalibrationLive;
private ArdupilotMega.Controls.MyButton BUT_MagCalibrationLive;
private System.Windows.Forms.Label label27;
private System.Windows.Forms.ComboBox CMB_sonartype;
private System.Windows.Forms.CheckBox CHK_enableoptflow;
@ -216,7 +216,7 @@
private System.Windows.Forms.PictureBox pictureBox4;
private System.Windows.Forms.PictureBox pictureBox3;
private System.Windows.Forms.PictureBox pictureBox1;
private MyButton BUT_MagCalibrationLog;
private ArdupilotMega.Controls.MyButton BUT_MagCalibrationLog;
private System.Windows.Forms.CheckBox CHK_autodec;
}
}

View File

@ -7,6 +7,7 @@ using System.Linq;
using System.Text;
using System.Windows.Forms;
using ArdupilotMega.Controls.BackstageView;
using ArdupilotMega.Controls;
namespace ArdupilotMega.GCSViews.ConfigurationView
{

View File

@ -139,7 +139,7 @@
<value>BUT_MagCalibrationLive</value>
</data>
<data name="&gt;&gt;BUT_MagCalibrationLive.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4491.32704, Culture=neutral, PublicKeyToken=null</value>
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4491.32704, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;BUT_MagCalibrationLive.Parent" xml:space="preserve">
<value>$this</value>
@ -526,7 +526,7 @@
<value>BUT_MagCalibrationLog</value>
</data>
<data name="&gt;&gt;BUT_MagCalibrationLog.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4491.32704, Culture=neutral, PublicKeyToken=null</value>
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4491.32704, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;BUT_MagCalibrationLog.Parent" xml:space="preserve">
<value>$this</value>

View File

@ -71,9 +71,9 @@
this.CHK_hudshow = new System.Windows.Forms.CheckBox();
this.label92 = new System.Windows.Forms.Label();
this.CMB_videosources = new System.Windows.Forms.ComboBox();
this.BUT_Joystick = new ArdupilotMega.MyButton();
this.BUT_videostop = new ArdupilotMega.MyButton();
this.BUT_videostart = new ArdupilotMega.MyButton();
this.BUT_Joystick = new ArdupilotMega.Controls.MyButton();
this.BUT_videostop = new ArdupilotMega.Controls.MyButton();
this.BUT_videostart = new ArdupilotMega.Controls.MyButton();
((System.ComponentModel.ISupportInitialize)(this.NUM_tracklength)).BeginInit();
this.SuspendLayout();
//
@ -512,8 +512,8 @@
private System.Windows.Forms.CheckBox CHK_hudshow;
private System.Windows.Forms.Label label92;
private System.Windows.Forms.ComboBox CMB_videosources;
private MyButton BUT_Joystick;
private MyButton BUT_videostop;
private MyButton BUT_videostart;
private ArdupilotMega.Controls.MyButton BUT_Joystick;
private ArdupilotMega.Controls.MyButton BUT_videostop;
private ArdupilotMega.Controls.MyButton BUT_videostart;
}
}

View File

@ -10,6 +10,7 @@ using System.Text;
using System.Windows.Forms;
using DirectShowLib;
using ArdupilotMega.Controls.BackstageView;
using ArdupilotMega.Controls;
namespace ArdupilotMega.GCSViews.ConfigurationView
{

View File

@ -1268,7 +1268,7 @@
<value>BUT_Joystick</value>
</data>
<data name="&gt;&gt;BUT_Joystick.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null</value>
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;BUT_Joystick.Parent" xml:space="preserve">
<value>$this</value>
@ -1295,7 +1295,7 @@
<value>BUT_videostop</value>
</data>
<data name="&gt;&gt;BUT_videostop.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null</value>
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;BUT_videostop.Parent" xml:space="preserve">
<value>$this</value>
@ -1322,7 +1322,7 @@
<value>BUT_videostart</value>
</data>
<data name="&gt;&gt;BUT_videostart.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null</value>
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;BUT_videostart.Parent" xml:space="preserve">
<value>$this</value>

View File

@ -39,7 +39,7 @@
this.CHK_revch4 = new System.Windows.Forms.CheckBox();
this.CHK_revch2 = new System.Windows.Forms.CheckBox();
this.CHK_revch1 = new System.Windows.Forms.CheckBox();
this.BUT_Calibrateradio = new ArdupilotMega.MyButton();
this.BUT_Calibrateradio = new ArdupilotMega.Controls.MyButton();
this.BAR8 = new ArdupilotMega.HorizontalProgressBar2();
this.currentStateBindingSource = new System.Windows.Forms.BindingSource(this.components);
this.BAR7 = new ArdupilotMega.HorizontalProgressBar2();
@ -289,7 +289,7 @@
private System.Windows.Forms.CheckBox CHK_revch4;
private System.Windows.Forms.CheckBox CHK_revch2;
private System.Windows.Forms.CheckBox CHK_revch1;
private MyButton BUT_Calibrateradio;
private ArdupilotMega.Controls.MyButton BUT_Calibrateradio;
private HorizontalProgressBar2 BAR8;
private HorizontalProgressBar2 BAR7;
private HorizontalProgressBar2 BAR6;

View File

@ -7,6 +7,7 @@ using System.Linq;
using System.Text;
using System.Windows.Forms;
using ArdupilotMega.Controls.BackstageView;
using ArdupilotMega.Controls;
namespace ArdupilotMega.GCSViews.ConfigurationView
{

View File

@ -403,7 +403,7 @@
<value>BUT_Calibrateradio</value>
</data>
<data name="&gt;&gt;BUT_Calibrateradio.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value>
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;BUT_Calibrateradio.Parent" xml:space="preserve">
<value>$this</value>

View File

@ -32,11 +32,11 @@
System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(ConfigRawParams));
System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle1 = new System.Windows.Forms.DataGridViewCellStyle();
System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle2 = new System.Windows.Forms.DataGridViewCellStyle();
this.BUT_compare = new ArdupilotMega.MyButton();
this.BUT_rerequestparams = new ArdupilotMega.MyButton();
this.BUT_writePIDS = new ArdupilotMega.MyButton();
this.BUT_save = new ArdupilotMega.MyButton();
this.BUT_load = new ArdupilotMega.MyButton();
this.BUT_compare = new ArdupilotMega.Controls.MyButton();
this.BUT_rerequestparams = new ArdupilotMega.Controls.MyButton();
this.BUT_writePIDS = new ArdupilotMega.Controls.MyButton();
this.BUT_save = new ArdupilotMega.Controls.MyButton();
this.BUT_load = new ArdupilotMega.Controls.MyButton();
this.Params = new System.Windows.Forms.DataGridView();
this.Command = new System.Windows.Forms.DataGridViewTextBoxColumn();
this.Value = new System.Windows.Forms.DataGridViewTextBoxColumn();
@ -159,11 +159,11 @@
#endregion
private MyButton BUT_compare;
private MyButton BUT_rerequestparams;
private MyButton BUT_writePIDS;
private MyButton BUT_save;
private MyButton BUT_load;
private ArdupilotMega.Controls.MyButton BUT_compare;
private ArdupilotMega.Controls.MyButton BUT_rerequestparams;
private ArdupilotMega.Controls.MyButton BUT_writePIDS;
private ArdupilotMega.Controls.MyButton BUT_save;
private ArdupilotMega.Controls.MyButton BUT_load;
private System.Windows.Forms.DataGridView Params;
private System.Windows.Forms.DataGridViewTextBoxColumn Command;
private System.Windows.Forms.DataGridViewTextBoxColumn Value;

View File

@ -10,6 +10,7 @@ using System.Text;
using System.Windows.Forms;
using log4net;
using ArdupilotMega.Controls.BackstageView;
using ArdupilotMega.Controls;
namespace ArdupilotMega.GCSViews.ConfigurationView
{

View File

@ -142,7 +142,7 @@
<value>BUT_compare</value>
</data>
<data name="&gt;&gt;BUT_compare.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null</value>
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;BUT_compare.Parent" xml:space="preserve">
<value>$this</value>
@ -172,7 +172,7 @@
<value>BUT_rerequestparams</value>
</data>
<data name="&gt;&gt;BUT_rerequestparams.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null</value>
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;BUT_rerequestparams.Parent" xml:space="preserve">
<value>$this</value>
@ -202,7 +202,7 @@
<value>BUT_writePIDS</value>
</data>
<data name="&gt;&gt;BUT_writePIDS.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null</value>
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;BUT_writePIDS.Parent" xml:space="preserve">
<value>$this</value>
@ -235,7 +235,7 @@
<value>BUT_save</value>
</data>
<data name="&gt;&gt;BUT_save.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null</value>
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;BUT_save.Parent" xml:space="preserve">
<value>$this</value>
@ -268,7 +268,7 @@
<value>BUT_load</value>
</data>
<data name="&gt;&gt;BUT_load.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null</value>
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4491.33622, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;BUT_load.Parent" xml:space="preserve">
<value>$this</value>

View File

@ -33,20 +33,20 @@
this.groupBox5 = new System.Windows.Forms.GroupBox();
this.H_SWASH_TYPE = new System.Windows.Forms.RadioButton();
this.CCPM = new System.Windows.Forms.RadioButton();
this.BUT_swash_manual = new ArdupilotMega.MyButton();
this.BUT_swash_manual = new ArdupilotMega.Controls.MyButton();
this.label41 = new System.Windows.Forms.Label();
this.groupBox3 = new System.Windows.Forms.GroupBox();
this.label46 = new System.Windows.Forms.Label();
this.label45 = new System.Windows.Forms.Label();
this.H_GYR_ENABLE = new System.Windows.Forms.CheckBox();
this.H_GYR_GAIN = new System.Windows.Forms.TextBox();
this.BUT_HS4save = new ArdupilotMega.MyButton();
this.BUT_HS4save = new ArdupilotMega.Controls.MyButton();
this.label21 = new System.Windows.Forms.Label();
this.H_COL_MIN = new System.Windows.Forms.TextBox();
this.groupBox1 = new System.Windows.Forms.GroupBox();
this.H_COL_MID = new System.Windows.Forms.TextBox();
this.H_COL_MAX = new System.Windows.Forms.TextBox();
this.BUT_0collective = new ArdupilotMega.MyButton();
this.BUT_0collective = new ArdupilotMega.Controls.MyButton();
this.groupBox2 = new System.Windows.Forms.GroupBox();
this.label24 = new System.Windows.Forms.Label();
this.HS4_MIN = new System.Windows.Forms.TextBox();
@ -709,20 +709,20 @@
private System.Windows.Forms.GroupBox groupBox5;
private System.Windows.Forms.RadioButton H_SWASH_TYPE;
private System.Windows.Forms.RadioButton CCPM;
private MyButton BUT_swash_manual;
private ArdupilotMega.Controls.MyButton BUT_swash_manual;
private System.Windows.Forms.Label label41;
private System.Windows.Forms.GroupBox groupBox3;
private System.Windows.Forms.Label label46;
private System.Windows.Forms.Label label45;
private System.Windows.Forms.CheckBox H_GYR_ENABLE;
private System.Windows.Forms.TextBox H_GYR_GAIN;
private MyButton BUT_HS4save;
private ArdupilotMega.Controls.MyButton BUT_HS4save;
private System.Windows.Forms.Label label21;
private System.Windows.Forms.TextBox H_COL_MIN;
private System.Windows.Forms.GroupBox groupBox1;
private System.Windows.Forms.TextBox H_COL_MID;
private System.Windows.Forms.TextBox H_COL_MAX;
private MyButton BUT_0collective;
private ArdupilotMega.Controls.MyButton BUT_0collective;
private System.Windows.Forms.GroupBox groupBox2;
private System.Windows.Forms.Label label24;
private System.Windows.Forms.TextBox HS4_MIN;

View File

@ -7,6 +7,7 @@ using System.Linq;
using System.Text;
using System.Windows.Forms;
using ArdupilotMega.Controls.BackstageView;
using ArdupilotMega.Controls;
namespace ArdupilotMega.GCSViews.ConfigurationView
{
@ -428,7 +429,7 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
}
if (control[0].GetType() == typeof(MyTrackBar))
{
MyTrackBar temp = (MyTrackBar)control[0];
ArdupilotMega.Controls.MyTrackBar temp = (MyTrackBar)control[0];
string option = MainV2.comPort.param[value].ToString();
temp.Value = int.Parse(option);
}

View File

@ -217,7 +217,7 @@
<value>BUT_swash_manual</value>
</data>
<data name="&gt;&gt;BUT_swash_manual.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4494.24488, Culture=neutral, PublicKeyToken=null</value>
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4494.24488, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;BUT_swash_manual.Parent" xml:space="preserve">
<value>$this</value>
@ -409,7 +409,7 @@
<value>BUT_HS4save</value>
</data>
<data name="&gt;&gt;BUT_HS4save.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4494.24488, Culture=neutral, PublicKeyToken=null</value>
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4494.24488, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;BUT_HS4save.Parent" xml:space="preserve">
<value>$this</value>
@ -550,7 +550,7 @@
<value>BUT_0collective</value>
</data>
<data name="&gt;&gt;BUT_0collective.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4494.24488, Culture=neutral, PublicKeyToken=null</value>
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4494.24488, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;BUT_0collective.Parent" xml:space="preserve">
<value>groupBox1</value>

View File

@ -20,7 +20,8 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
this.backstageView.AddPage(new BackstageView.BackstageViewPage(new ConfigFlightModes(), "Flight Modes"));
this.backstageView.AddPage(new BackstageView.BackstageViewPage(new ConfigHardwareOptions(), "Hardware Options"));
this.backstageView.AddPage(new BackstageView.BackstageViewPage(new ConfigBatteryMonitoring(), "Battery Monitor"));
this.backstageView.AddPage(new BackstageView.BackstageViewPage(new ConfigAccelerometerCalibrationQuad(), "Level Calibration"));
this.backstageView.AddPage(new BackstageView.BackstageViewPage(new ConfigAccelerometerCalibrationQuad(), "ArduCopter"));
this.backstageView.AddPage(new BackstageView.BackstageViewPage(new ConfigAccelerometerCalibrationPlane(), "ArduPlane"));
this.backstageView.AddPage(new BackstageView.BackstageViewPage(new ConfigArducopter(), "Arducopter Setup"));
this.backstageView.AddPage(new BackstageView.BackstageViewPage(new ConfigArduplane(), "Arduplane Setup"));
this.backstageView.AddPage(new BackstageView.BackstageViewPage(new ConfigTradHeli(), "Heli Setup"));

View File

@ -24,6 +24,8 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
this.backstageView.AddPage(new BackstageView.BackstageViewPage(new ConfigAccelerometerCalibrationPlane(), "ArduPlane Level"));
this.backstageView.AddPage(new BackstageView.BackstageViewPage(new ConfigTradHeli(), "Heli Setup"));
this.backstageView.AddPage(new BackstageView.BackstageViewPage(new ConfigRawParams(), "Raw params (Advanced)"));
this.backstageView.AddPage(new BackstageView.BackstageViewPage(new ArdupilotMega._3DRradio(), "3DR Radio"));
this.backstageView.AddPage(new BackstageView.BackstageViewPage(new ArdupilotMega.Antenna.Tracker(), "Antenna Tracker"));

View File

@ -36,43 +36,43 @@ namespace ArdupilotMega.GCSViews
}
private ImageLabel pictureBoxAPM;
private ImageLabel pictureBoxQuad;
private ImageLabel pictureBoxHexa;
private ImageLabel pictureBoxTri;
private ImageLabel pictureBoxY6;
private ArdupilotMega.Controls.ImageLabel pictureBoxAPM;
private ArdupilotMega.Controls.ImageLabel pictureBoxQuad;
private ArdupilotMega.Controls.ImageLabel pictureBoxHexa;
private ArdupilotMega.Controls.ImageLabel pictureBoxTri;
private ArdupilotMega.Controls.ImageLabel pictureBoxY6;
private System.Windows.Forms.Label lbl_status;
private System.Windows.Forms.ProgressBar progress;
private System.Windows.Forms.Label label2;
private ImageLabel pictureBoxHeli;
private MyButton BUT_setup;
private ArdupilotMega.Controls.ImageLabel pictureBoxHeli;
private ArdupilotMega.Controls.MyButton BUT_setup;
private PictureBox pictureBoxHilimage;
private PictureBox pictureBoxAPHil;
private PictureBox pictureBoxACHil;
private PictureBox pictureBoxACHHil;
private ImageLabel pictureBoxOcta;
private ArdupilotMega.Controls.ImageLabel pictureBoxOcta;
private Label label1;
private ImageLabel pictureBoxOctav;
private ArdupilotMega.Controls.ImageLabel pictureBoxOctav;
private void InitializeComponent()
{
System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(Firmware));
this.pictureBoxAPM = new ArdupilotMega.ImageLabel();
this.pictureBoxQuad = new ArdupilotMega.ImageLabel();
this.pictureBoxHexa = new ArdupilotMega.ImageLabel();
this.pictureBoxTri = new ArdupilotMega.ImageLabel();
this.pictureBoxY6 = new ArdupilotMega.ImageLabel();
this.pictureBoxAPM = new ArdupilotMega.Controls.ImageLabel();
this.pictureBoxQuad = new ArdupilotMega.Controls.ImageLabel();
this.pictureBoxHexa = new ArdupilotMega.Controls.ImageLabel();
this.pictureBoxTri = new ArdupilotMega.Controls.ImageLabel();
this.pictureBoxY6 = new ArdupilotMega.Controls.ImageLabel();
this.lbl_status = new System.Windows.Forms.Label();
this.progress = new System.Windows.Forms.ProgressBar();
this.label2 = new System.Windows.Forms.Label();
this.pictureBoxHeli = new ArdupilotMega.ImageLabel();
this.BUT_setup = new ArdupilotMega.MyButton();
this.pictureBoxHeli = new ArdupilotMega.Controls.ImageLabel();
this.BUT_setup = new ArdupilotMega.Controls.MyButton();
this.pictureBoxHilimage = new System.Windows.Forms.PictureBox();
this.pictureBoxAPHil = new System.Windows.Forms.PictureBox();
this.pictureBoxACHil = new System.Windows.Forms.PictureBox();
this.pictureBoxACHHil = new System.Windows.Forms.PictureBox();
this.pictureBoxOcta = new ArdupilotMega.ImageLabel();
this.pictureBoxOctav = new ArdupilotMega.ImageLabel();
this.pictureBoxOcta = new ArdupilotMega.Controls.ImageLabel();
this.pictureBoxOctav = new ArdupilotMega.Controls.ImageLabel();
this.label1 = new System.Windows.Forms.Label();
((System.ComponentModel.ISupportInitialize)(this.pictureBoxHilimage)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.pictureBoxAPHil)).BeginInit();

View File

@ -7,6 +7,7 @@ using System.IO;
using System.Xml;
using System.Net;
using log4net;
using ArdupilotMega.Arduino;
namespace ArdupilotMega.GCSViews
{
@ -223,42 +224,6 @@ namespace ArdupilotMega.GCSViews
}
return;
}
else if (items.Count == 2 && false)
{
XorPlus select = new XorPlus();
ThemeManager.ApplyThemeTo(select);
select.ShowDialog();
int a = 0;
if (select.frame == "")
{
return;
}
foreach (software temp in items)
{
if (select.frame == "+" && temp.name.Contains("Plus"))
{
DialogResult dr = CustomMessageBox.Show("Are you sure you want to upload " + items[a].name + "?", "Continue", MessageBoxButtons.YesNo);
if (dr == System.Windows.Forms.DialogResult.Yes)
{
update(items[a]);
return;
}
}
else if (select.frame == "X" && temp.name.Contains("X"))
{
DialogResult dr = CustomMessageBox.Show("Are you sure you want to upload " + items[a].name + "?", "Continue", MessageBoxButtons.YesNo);
if (dr == System.Windows.Forms.DialogResult.Yes)
{
update(items[a]);
return;
}
}
a++;
}
}
else
{
CustomMessageBox.Show("Something has gone wrong, to many firmware choices");

View File

@ -367,7 +367,7 @@
<value>BUT_setup</value>
</data>
<data name="&gt;&gt;BUT_setup.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
</data>
<data name="&gt;&gt;BUT_setup.Parent" xml:space="preserve">
<value>$this</value>

View File

@ -15,28 +15,28 @@
this.pointCameraHereToolStripMenuItem = new System.Windows.Forms.ToolStripMenuItem();
this.MainH = new System.Windows.Forms.SplitContainer();
this.SubMainLeft = new System.Windows.Forms.SplitContainer();
this.hud1 = new hud.HUD();
this.hud1 = new ArdupilotMega.Controls.HUD();
this.contextMenuStrip2 = new System.Windows.Forms.ContextMenuStrip(this.components);
this.recordHudToAVIToolStripMenuItem = new System.Windows.Forms.ToolStripMenuItem();
this.stopRecordToolStripMenuItem = new System.Windows.Forms.ToolStripMenuItem();
this.bindingSource1 = new System.Windows.Forms.BindingSource(this.components);
this.tabControl1 = new System.Windows.Forms.TabControl();
this.tabActions = new System.Windows.Forms.TabPage();
this.BUT_script = new ArdupilotMega.MyButton();
this.BUT_joystick = new ArdupilotMega.MyButton();
this.BUT_quickmanual = new ArdupilotMega.MyButton();
this.BUT_quickrtl = new ArdupilotMega.MyButton();
this.BUT_quickauto = new ArdupilotMega.MyButton();
this.BUT_script = new ArdupilotMega.Controls.MyButton();
this.BUT_joystick = new ArdupilotMega.Controls.MyButton();
this.BUT_quickmanual = new ArdupilotMega.Controls.MyButton();
this.BUT_quickrtl = new ArdupilotMega.Controls.MyButton();
this.BUT_quickauto = new ArdupilotMega.Controls.MyButton();
this.CMB_setwp = new System.Windows.Forms.ComboBox();
this.BUT_setwp = new ArdupilotMega.MyButton();
this.BUT_setwp = new ArdupilotMega.Controls.MyButton();
this.CMB_modes = new System.Windows.Forms.ComboBox();
this.BUT_setmode = new ArdupilotMega.MyButton();
this.BUT_clear_track = new ArdupilotMega.MyButton();
this.BUT_setmode = new ArdupilotMega.Controls.MyButton();
this.BUT_clear_track = new ArdupilotMega.Controls.MyButton();
this.CMB_action = new System.Windows.Forms.ComboBox();
this.BUT_Homealt = new ArdupilotMega.MyButton();
this.BUT_RAWSensor = new ArdupilotMega.MyButton();
this.BUTrestartmission = new ArdupilotMega.MyButton();
this.BUTactiondo = new ArdupilotMega.MyButton();
this.BUT_Homealt = new ArdupilotMega.Controls.MyButton();
this.BUT_RAWSensor = new ArdupilotMega.Controls.MyButton();
this.BUTrestartmission = new ArdupilotMega.Controls.MyButton();
this.BUTactiondo = new ArdupilotMega.Controls.MyButton();
this.tabGauges = new System.Windows.Forms.TabPage();
this.Gvspeed = new AGaugeApp.AGauge();
this.Gheading = new AGaugeApp.AGauge();
@ -44,33 +44,33 @@
this.Gspeed = new AGaugeApp.AGauge();
this.tabStatus = new System.Windows.Forms.TabPage();
this.tabTLogs = new System.Windows.Forms.TabPage();
this.lbl_logpercent = new ArdupilotMega.MyLabel();
this.lbl_logpercent = new ArdupilotMega.Controls.MyLabel();
this.NUM_playbackspeed = new System.Windows.Forms.NumericUpDown();
this.BUT_log2kml = new ArdupilotMega.MyButton();
this.BUT_log2kml = new ArdupilotMega.Controls.MyButton();
this.tracklog = new System.Windows.Forms.TrackBar();
this.BUT_playlog = new ArdupilotMega.MyButton();
this.BUT_loadtelem = new ArdupilotMega.MyButton();
this.BUT_playlog = new ArdupilotMega.Controls.MyButton();
this.BUT_loadtelem = new ArdupilotMega.Controls.MyButton();
this.tableMap = new System.Windows.Forms.TableLayoutPanel();
this.splitContainer1 = new System.Windows.Forms.SplitContainer();
this.zg1 = new ZedGraph.ZedGraphControl();
this.lbl_hdop = new ArdupilotMega.MyLabel();
this.lbl_sats = new ArdupilotMega.MyLabel();
this.lbl_winddir = new ArdupilotMega.MyLabel();
this.lbl_windvel = new ArdupilotMega.MyLabel();
this.gMapControl1 = new ArdupilotMega.myGMAP();
this.lbl_hdop = new ArdupilotMega.Controls.MyLabel();
this.lbl_sats = new ArdupilotMega.Controls.MyLabel();
this.lbl_winddir = new ArdupilotMega.Controls.MyLabel();
this.lbl_windvel = new ArdupilotMega.Controls.MyLabel();
this.gMapControl1 = new ArdupilotMega.Controls.myGMAP();
this.panel1 = new System.Windows.Forms.Panel();
this.TXT_lat = new ArdupilotMega.MyLabel();
this.TXT_lat = new ArdupilotMega.Controls.MyLabel();
this.Zoomlevel = new System.Windows.Forms.NumericUpDown();
this.label1 = new ArdupilotMega.MyLabel();
this.TXT_long = new ArdupilotMega.MyLabel();
this.TXT_alt = new ArdupilotMega.MyLabel();
this.label1 = new ArdupilotMega.Controls.MyLabel();
this.TXT_long = new ArdupilotMega.Controls.MyLabel();
this.TXT_alt = new ArdupilotMega.Controls.MyLabel();
this.CHK_autopan = new System.Windows.Forms.CheckBox();
this.CB_tuning = new System.Windows.Forms.CheckBox();
this.dataGridViewImageColumn1 = new System.Windows.Forms.DataGridViewImageColumn();
this.dataGridViewImageColumn2 = new System.Windows.Forms.DataGridViewImageColumn();
this.ZedGraphTimer = new System.Windows.Forms.Timer(this.components);
this.toolTip1 = new System.Windows.Forms.ToolTip(this.components);
this.label6 = new ArdupilotMega.MyLabel();
this.label6 = new ArdupilotMega.Controls.MyLabel();
this.contextMenuStrip1.SuspendLayout();
this.MainH.Panel1.SuspendLayout();
this.MainH.Panel2.SuspendLayout();
@ -1311,37 +1311,37 @@
private System.Windows.Forms.DataGridViewImageColumn dataGridViewImageColumn1;
private System.Windows.Forms.DataGridViewImageColumn dataGridViewImageColumn2;
private ArdupilotMega.MyLabel label6;
private ArdupilotMega.Controls.MyLabel label6;
private System.Windows.Forms.BindingSource bindingSource1;
private System.Windows.Forms.Timer ZedGraphTimer;
private System.Windows.Forms.SplitContainer MainH;
private System.Windows.Forms.SplitContainer SubMainLeft;
private System.Windows.Forms.ContextMenuStrip contextMenuStrip1;
private System.Windows.Forms.ToolStripMenuItem goHereToolStripMenuItem;
private hud.HUD hud1;
private MyButton BUT_clear_track;
private ArdupilotMega.Controls.HUD hud1;
private ArdupilotMega.Controls.MyButton BUT_clear_track;
private System.Windows.Forms.CheckBox CB_tuning;
private MyButton BUT_RAWSensor;
private MyButton BUTactiondo;
private MyButton BUTrestartmission;
private ArdupilotMega.Controls.MyButton BUT_RAWSensor;
private ArdupilotMega.Controls.MyButton BUTactiondo;
private ArdupilotMega.Controls.MyButton BUTrestartmission;
private System.Windows.Forms.ComboBox CMB_action;
private MyButton BUT_Homealt;
private ArdupilotMega.Controls.MyButton BUT_Homealt;
private System.Windows.Forms.TrackBar tracklog;
private MyButton BUT_playlog;
private MyButton BUT_loadtelem;
private ArdupilotMega.Controls.MyButton BUT_playlog;
private ArdupilotMega.Controls.MyButton BUT_loadtelem;
private AGaugeApp.AGauge Gheading;
private AGaugeApp.AGauge Galt;
private AGaugeApp.AGauge Gspeed;
private AGaugeApp.AGauge Gvspeed;
private System.Windows.Forms.TableLayoutPanel tableMap;
private System.Windows.Forms.Panel panel1;
private ArdupilotMega.MyLabel TXT_lat;
private ArdupilotMega.Controls.MyLabel TXT_lat;
private System.Windows.Forms.NumericUpDown Zoomlevel;
private ArdupilotMega.MyLabel label1;
private ArdupilotMega.MyLabel TXT_long;
private ArdupilotMega.MyLabel TXT_alt;
private ArdupilotMega.Controls.MyLabel label1;
private ArdupilotMega.Controls.MyLabel TXT_long;
private ArdupilotMega.Controls.MyLabel TXT_alt;
private System.Windows.Forms.CheckBox CHK_autopan;
private myGMAP gMapControl1;
private ArdupilotMega.Controls.myGMAP gMapControl1;
private ZedGraph.ZedGraphControl zg1;
private System.Windows.Forms.TabControl tabControl1;
private System.Windows.Forms.TabPage tabGauges;
@ -1349,26 +1349,26 @@
private System.Windows.Forms.TabPage tabActions;
private System.Windows.Forms.TabPage tabTLogs;
private System.Windows.Forms.ComboBox CMB_modes;
private MyButton BUT_setmode;
private ArdupilotMega.Controls.MyButton BUT_setmode;
private System.Windows.Forms.ComboBox CMB_setwp;
private MyButton BUT_setwp;
private MyButton BUT_quickmanual;
private MyButton BUT_quickrtl;
private MyButton BUT_quickauto;
private MyButton BUT_log2kml;
private ArdupilotMega.MyLabel lbl_windvel;
private ArdupilotMega.MyLabel lbl_winddir;
private MyButton BUT_joystick;
private ArdupilotMega.Controls.MyButton BUT_setwp;
private ArdupilotMega.Controls.MyButton BUT_quickmanual;
private ArdupilotMega.Controls.MyButton BUT_quickrtl;
private ArdupilotMega.Controls.MyButton BUT_quickauto;
private ArdupilotMega.Controls.MyButton BUT_log2kml;
private ArdupilotMega.Controls.MyLabel lbl_windvel;
private ArdupilotMega.Controls.MyLabel lbl_winddir;
private ArdupilotMega.Controls.MyButton BUT_joystick;
private System.Windows.Forms.ToolTip toolTip1;
private System.Windows.Forms.NumericUpDown NUM_playbackspeed;
private System.Windows.Forms.ContextMenuStrip contextMenuStrip2;
private System.Windows.Forms.ToolStripMenuItem recordHudToAVIToolStripMenuItem;
private System.Windows.Forms.ToolStripMenuItem stopRecordToolStripMenuItem;
private MyLabel lbl_logpercent;
private ArdupilotMega.Controls.MyLabel lbl_logpercent;
private System.Windows.Forms.ToolStripMenuItem pointCameraHereToolStripMenuItem;
private System.Windows.Forms.SplitContainer splitContainer1;
private MyButton BUT_script;
private MyLabel lbl_hdop;
private MyLabel lbl_sats;
private ArdupilotMega.Controls.MyButton BUT_script;
private ArdupilotMega.Controls.MyLabel lbl_hdop;
private ArdupilotMega.Controls.MyLabel lbl_sats;
}
}

View File

@ -16,6 +16,8 @@ using System.Globalization; // language
using GMap.NET.WindowsForms.Markers;
using ZedGraph; // Graphs
using System.Drawing.Drawing2D;
using ArdupilotMega.Controls;
using ArdupilotMega.Utilities;
// written by michael oborne
namespace ArdupilotMega.GCSViews
@ -71,7 +73,7 @@ namespace ArdupilotMega.GCSViews
const float deg2rad = (float)(1.0 / rad2deg);
public static hud.HUD myhud = null;
public static ArdupilotMega.Controls.HUD myhud = null;
public static GMapControl mymap = null;
bool playingLog = false;
@ -1224,7 +1226,9 @@ namespace ArdupilotMega.GCSViews
private void CMB_modes_Click(object sender, EventArgs e)
{
CMB_modes.DataSource = Enum.GetNames(Common.getModes());
CMB_modes.DataSource = Common.getModesList();
CMB_modes.ValueMember = "Key";
CMB_modes.DisplayMember = "Value";
}
private void hud1_DoubleClick(object sender, EventArgs e)

View File

@ -208,7 +208,7 @@
<value>hud1</value>
</data>
<data name="&gt;&gt;hud1.Type" xml:space="preserve">
<value>hud.HUD, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null</value>
<value>hud.HUD, ArdupilotMegaPlanner, Version=1.1.4497.35992, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;hud1.Parent" xml:space="preserve">
<value>SubMainLeft.Panel1</value>
@ -247,7 +247,7 @@
<value>BUT_script</value>
</data>
<data name="&gt;&gt;BUT_script.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null</value>
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4497.35992, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;BUT_script.Parent" xml:space="preserve">
<value>tabActions</value>
@ -280,7 +280,7 @@
<value>BUT_joystick</value>
</data>
<data name="&gt;&gt;BUT_joystick.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null</value>
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4497.35992, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;BUT_joystick.Parent" xml:space="preserve">
<value>tabActions</value>
@ -310,7 +310,7 @@
<value>BUT_quickmanual</value>
</data>
<data name="&gt;&gt;BUT_quickmanual.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null</value>
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4497.35992, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;BUT_quickmanual.Parent" xml:space="preserve">
<value>tabActions</value>
@ -340,7 +340,7 @@
<value>BUT_quickrtl</value>
</data>
<data name="&gt;&gt;BUT_quickrtl.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null</value>
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4497.35992, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;BUT_quickrtl.Parent" xml:space="preserve">
<value>tabActions</value>
@ -370,7 +370,7 @@
<value>BUT_quickauto</value>
</data>
<data name="&gt;&gt;BUT_quickauto.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null</value>
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4497.35992, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;BUT_quickauto.Parent" xml:space="preserve">
<value>tabActions</value>
@ -424,7 +424,7 @@
<value>BUT_setwp</value>
</data>
<data name="&gt;&gt;BUT_setwp.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null</value>
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4497.35992, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;BUT_setwp.Parent" xml:space="preserve">
<value>tabActions</value>
@ -475,7 +475,7 @@
<value>BUT_setmode</value>
</data>
<data name="&gt;&gt;BUT_setmode.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null</value>
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4497.35992, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;BUT_setmode.Parent" xml:space="preserve">
<value>tabActions</value>
@ -505,7 +505,7 @@
<value>BUT_clear_track</value>
</data>
<data name="&gt;&gt;BUT_clear_track.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null</value>
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4497.35992, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;BUT_clear_track.Parent" xml:space="preserve">
<value>tabActions</value>
@ -556,7 +556,7 @@
<value>BUT_Homealt</value>
</data>
<data name="&gt;&gt;BUT_Homealt.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null</value>
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4497.35992, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;BUT_Homealt.Parent" xml:space="preserve">
<value>tabActions</value>
@ -586,7 +586,7 @@
<value>BUT_RAWSensor</value>
</data>
<data name="&gt;&gt;BUT_RAWSensor.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null</value>
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4497.35992, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;BUT_RAWSensor.Parent" xml:space="preserve">
<value>tabActions</value>
@ -616,7 +616,7 @@
<value>BUTrestartmission</value>
</data>
<data name="&gt;&gt;BUTrestartmission.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null</value>
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4497.35992, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;BUTrestartmission.Parent" xml:space="preserve">
<value>tabActions</value>
@ -646,7 +646,7 @@
<value>BUTactiondo</value>
</data>
<data name="&gt;&gt;BUTactiondo.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null</value>
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4497.35992, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;BUTactiondo.Parent" xml:space="preserve">
<value>tabActions</value>
@ -700,7 +700,7 @@
<value>Gvspeed</value>
</data>
<data name="&gt;&gt;Gvspeed.Type" xml:space="preserve">
<value>AGaugeApp.AGauge, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null</value>
<value>AGaugeApp.AGauge, ArdupilotMegaPlanner, Version=1.1.4497.35992, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;Gvspeed.Parent" xml:space="preserve">
<value>tabGauges</value>
@ -730,7 +730,7 @@
<value>Gheading</value>
</data>
<data name="&gt;&gt;Gheading.Type" xml:space="preserve">
<value>AGaugeApp.AGauge, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null</value>
<value>AGaugeApp.AGauge, ArdupilotMegaPlanner, Version=1.1.4497.35992, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;Gheading.Parent" xml:space="preserve">
<value>tabGauges</value>
@ -760,7 +760,7 @@
<value>Galt</value>
</data>
<data name="&gt;&gt;Galt.Type" xml:space="preserve">
<value>AGaugeApp.AGauge, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null</value>
<value>AGaugeApp.AGauge, ArdupilotMegaPlanner, Version=1.1.4497.35992, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;Galt.Parent" xml:space="preserve">
<value>tabGauges</value>
@ -793,7 +793,7 @@
<value>Gspeed</value>
</data>
<data name="&gt;&gt;Gspeed.Type" xml:space="preserve">
<value>AGaugeApp.AGauge, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null</value>
<value>AGaugeApp.AGauge, ArdupilotMegaPlanner, Version=1.1.4497.35992, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;Gspeed.Parent" xml:space="preserve">
<value>tabGauges</value>
@ -874,7 +874,7 @@
<value>lbl_logpercent</value>
</data>
<data name="&gt;&gt;lbl_logpercent.Type" xml:space="preserve">
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null</value>
<value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.1.4497.35992, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;lbl_logpercent.Parent" xml:space="preserve">
<value>tabTLogs</value>
@ -925,7 +925,7 @@
<value>BUT_log2kml</value>
</data>
<data name="&gt;&gt;BUT_log2kml.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null</value>
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4497.35992, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;BUT_log2kml.Parent" xml:space="preserve">
<value>tabTLogs</value>
@ -976,7 +976,7 @@
<value>BUT_playlog</value>
</data>
<data name="&gt;&gt;BUT_playlog.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null</value>
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4497.35992, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;BUT_playlog.Parent" xml:space="preserve">
<value>tabTLogs</value>
@ -1003,7 +1003,7 @@
<value>BUT_loadtelem</value>
</data>
<data name="&gt;&gt;BUT_loadtelem.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null</value>
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4497.35992, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;BUT_loadtelem.Parent" xml:space="preserve">
<value>tabTLogs</value>
@ -1192,7 +1192,7 @@
<value>lbl_hdop</value>
</data>
<data name="&gt;&gt;lbl_hdop.Type" xml:space="preserve">
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null</value>
<value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.1.4497.35992, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;lbl_hdop.Parent" xml:space="preserve">
<value>splitContainer1.Panel2</value>
@ -1225,7 +1225,7 @@
<value>lbl_sats</value>
</data>
<data name="&gt;&gt;lbl_sats.Type" xml:space="preserve">
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null</value>
<value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.1.4497.35992, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;lbl_sats.Parent" xml:space="preserve">
<value>splitContainer1.Panel2</value>
@ -1255,7 +1255,7 @@
<value>lbl_winddir</value>
</data>
<data name="&gt;&gt;lbl_winddir.Type" xml:space="preserve">
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null</value>
<value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.1.4497.35992, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;lbl_winddir.Parent" xml:space="preserve">
<value>splitContainer1.Panel2</value>
@ -1285,7 +1285,7 @@
<value>lbl_windvel</value>
</data>
<data name="&gt;&gt;lbl_windvel.Type" xml:space="preserve">
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null</value>
<value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.1.4497.35992, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;lbl_windvel.Parent" xml:space="preserve">
<value>splitContainer1.Panel2</value>
@ -1457,7 +1457,7 @@
<value>gMapControl1</value>
</data>
<data name="&gt;&gt;gMapControl1.Type" xml:space="preserve">
<value>ArdupilotMega.myGMAP, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null</value>
<value>ArdupilotMega.Controls.myGMAP, ArdupilotMegaPlanner, Version=1.1.4497.35992, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;gMapControl1.Parent" xml:space="preserve">
<value>splitContainer1.Panel2</value>
@ -1520,7 +1520,7 @@
<value>TXT_lat</value>
</data>
<data name="&gt;&gt;TXT_lat.Type" xml:space="preserve">
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null</value>
<value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.1.4497.35992, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;TXT_lat.Parent" xml:space="preserve">
<value>panel1</value>
@ -1577,7 +1577,7 @@
<value>label1</value>
</data>
<data name="&gt;&gt;label1.Type" xml:space="preserve">
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null</value>
<value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.1.4497.35992, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;label1.Parent" xml:space="preserve">
<value>panel1</value>
@ -1607,7 +1607,7 @@
<value>TXT_long</value>
</data>
<data name="&gt;&gt;TXT_long.Type" xml:space="preserve">
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null</value>
<value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.1.4497.35992, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;TXT_long.Parent" xml:space="preserve">
<value>panel1</value>
@ -1637,7 +1637,7 @@
<value>TXT_alt</value>
</data>
<data name="&gt;&gt;TXT_alt.Type" xml:space="preserve">
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null</value>
<value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.1.4497.35992, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;TXT_alt.Parent" xml:space="preserve">
<value>panel1</value>
@ -1838,7 +1838,7 @@
<value>label6</value>
</data>
<data name="&gt;&gt;label6.Type" xml:space="preserve">
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null</value>
<value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.1.4497.35992, Culture=neutral, PublicKeyToken=null</value>
</data>
<data name="&gt;&gt;label6.Parent" xml:space="preserve">
<value>$this</value>
@ -1916,6 +1916,6 @@
<value>FlightData</value>
</data>
<data name="&gt;&gt;$this.Type" xml:space="preserve">
<value>System.Windows.Forms.MyUserControl, ArdupilotMegaPlanner, Version=1.1.4489.31102, Culture=neutral, PublicKeyToken=null</value>
<value>System.Windows.Forms.MyUserControl, ArdupilotMegaPlanner, Version=1.1.4497.35992, Culture=neutral, PublicKeyToken=null</value>
</data>
</root>

View File

@ -61,10 +61,10 @@
this.TXT_loiterrad = new System.Windows.Forms.TextBox();
this.label5 = new System.Windows.Forms.Label();
this.panel5 = new System.Windows.Forms.Panel();
this.BUT_write = new ArdupilotMega.MyButton();
this.BUT_read = new ArdupilotMega.MyButton();
this.SaveFile = new ArdupilotMega.MyButton();
this.BUT_loadwpfile = new ArdupilotMega.MyButton();
this.BUT_write = new ArdupilotMega.Controls.MyButton();
this.BUT_read = new ArdupilotMega.Controls.MyButton();
this.SaveFile = new ArdupilotMega.Controls.MyButton();
this.BUT_loadwpfile = new ArdupilotMega.Controls.MyButton();
this.panel1 = new System.Windows.Forms.Panel();
this.label4 = new System.Windows.Forms.LinkLabel();
this.label3 = new System.Windows.Forms.Label();
@ -89,19 +89,19 @@
this.textBox1 = new System.Windows.Forms.TextBox();
this.panelWaypoints = new BSE.Windows.Forms.Panel();
this.splitter1 = new BSE.Windows.Forms.Splitter();
this.BUT_loadkml = new ArdupilotMega.MyButton();
this.BUT_zoomto = new ArdupilotMega.MyButton();
this.BUT_Camera = new ArdupilotMega.MyButton();
this.BUT_grid = new ArdupilotMega.MyButton();
this.BUT_Prefetch = new ArdupilotMega.MyButton();
this.button1 = new ArdupilotMega.MyButton();
this.BUT_Add = new ArdupilotMega.MyButton();
this.BUT_loadkml = new ArdupilotMega.Controls.MyButton();
this.BUT_zoomto = new ArdupilotMega.Controls.MyButton();
this.BUT_Camera = new ArdupilotMega.Controls.MyButton();
this.BUT_grid = new ArdupilotMega.Controls.MyButton();
this.BUT_Prefetch = new ArdupilotMega.Controls.MyButton();
this.button1 = new ArdupilotMega.Controls.MyButton();
this.BUT_Add = new ArdupilotMega.Controls.MyButton();
this.panelAction = new BSE.Windows.Forms.Panel();
this.panelMap = new System.Windows.Forms.Panel();
this.lbl_distance = new System.Windows.Forms.Label();
this.lbl_homedist = new System.Windows.Forms.Label();
this.lbl_prevdist = new System.Windows.Forms.Label();
this.MainMap = new myGMAP();
this.MainMap = new ArdupilotMega.Controls.myGMAP();
this.contextMenuStrip1 = new System.Windows.Forms.ContextMenuStrip(this.components);
this.deleteWPToolStripMenuItem = new System.Windows.Forms.ToolStripMenuItem();
this.loiterToolStripMenuItem = new System.Windows.Forms.ToolStripMenuItem();
@ -123,7 +123,7 @@
this.GeoFencedownloadToolStripMenuItem = new System.Windows.Forms.ToolStripMenuItem();
this.setReturnLocationToolStripMenuItem = new System.Windows.Forms.ToolStripMenuItem();
this.loadFromFileToolStripMenuItem = new System.Windows.Forms.ToolStripMenuItem();
this.trackBar1 = new ArdupilotMega.MyTrackBar();
this.trackBar1 = new ArdupilotMega.Controls.MyTrackBar();
this.label11 = new System.Windows.Forms.Label();
this.panelBASE = new System.Windows.Forms.Panel();
this.toolTip1 = new System.Windows.Forms.ToolTip(this.components);
@ -932,9 +932,9 @@
#endregion
private MyButton SaveFile;
private MyButton BUT_read;
private MyButton BUT_write;
private ArdupilotMega.Controls.MyButton SaveFile;
private ArdupilotMega.Controls.MyButton BUT_read;
private ArdupilotMega.Controls.MyButton BUT_write;
private System.Windows.Forms.Panel panel5;
private System.Windows.Forms.Panel panel1;
private System.Windows.Forms.LinkLabel label4;
@ -955,12 +955,12 @@
private System.Windows.Forms.TextBox TXT_mousealt;
private System.Windows.Forms.TextBox TXT_mouselong;
private System.Windows.Forms.TextBox TXT_mouselat;
private MyButton BUT_loadwpfile;
private ArdupilotMega.Controls.MyButton BUT_loadwpfile;
private System.Windows.Forms.ComboBox comboBoxMapType;
private System.Windows.Forms.Label lbl_status;
private System.Windows.Forms.DataGridView Commands;
private System.Windows.Forms.CheckBox CHK_geheight;
private MyButton BUT_Add;
private ArdupilotMega.Controls.MyButton BUT_Add;
private System.Windows.Forms.TextBox TXT_WPRad;
private System.Windows.Forms.TextBox TXT_DefaultAlt;
private System.Windows.Forms.Label LBL_WPRad;
@ -968,21 +968,21 @@
private System.Windows.Forms.TextBox TXT_loiterrad;
private System.Windows.Forms.Label label5;
private System.Windows.Forms.CheckBox CHK_holdalt;
private MyButton button1;
private ArdupilotMega.Controls.MyButton button1;
private System.Windows.Forms.CheckBox CHK_altmode;
private BSE.Windows.Forms.Panel panelWaypoints;
private BSE.Windows.Forms.Panel panelAction;
private System.Windows.Forms.Panel panelMap;
private myGMAP MainMap;
private MyTrackBar trackBar1;
private ArdupilotMega.Controls.myGMAP MainMap;
private ArdupilotMega.Controls.MyTrackBar trackBar1;
private System.Windows.Forms.Label label11;
private System.Windows.Forms.Label lbl_distance;
private System.Windows.Forms.Label lbl_prevdist;
private BSE.Windows.Forms.Splitter splitter1;
private System.Windows.Forms.Panel panelBASE;
private System.Windows.Forms.Label lbl_homedist;
private MyButton BUT_Prefetch;
private MyButton BUT_grid;
private ArdupilotMega.Controls.MyButton BUT_Prefetch;
private ArdupilotMega.Controls.MyButton BUT_grid;
private System.Windows.Forms.ContextMenuStrip contextMenuStrip1;
private System.Windows.Forms.ToolStripMenuItem ContextMeasure;
private System.Windows.Forms.ToolTip toolTip1;
@ -1000,7 +1000,7 @@
private System.Windows.Forms.ToolStripMenuItem jumpwPToolStripMenuItem;
private System.Windows.Forms.ToolStripSeparator toolStripSeparator1;
private System.Windows.Forms.ToolStripMenuItem deleteWPToolStripMenuItem;
private MyButton BUT_Camera;
private ArdupilotMega.Controls.MyButton BUT_Camera;
private System.Windows.Forms.DataGridViewComboBoxColumn Command;
private System.Windows.Forms.DataGridViewTextBoxColumn Param1;
private System.Windows.Forms.DataGridViewTextBoxColumn Param2;
@ -1012,8 +1012,8 @@
private System.Windows.Forms.DataGridViewButtonColumn Delete;
private System.Windows.Forms.DataGridViewImageColumn Up;
private System.Windows.Forms.DataGridViewImageColumn Down;
private MyButton BUT_zoomto;
private MyButton BUT_loadkml;
private ArdupilotMega.Controls.MyButton BUT_zoomto;
private ArdupilotMega.Controls.MyButton BUT_loadkml;
private System.Windows.Forms.Timer timer1;
private System.Windows.Forms.ToolStripMenuItem geoFenceToolStripMenuItem;
private System.Windows.Forms.ToolStripMenuItem GeoFenceuploadToolStripMenuItem;

View File

@ -21,6 +21,7 @@ using System.Threading;
using log4net;
using SharpKml.Base;
using SharpKml.Dom;
using ArdupilotMega.Controls;

View File

@ -556,7 +556,7 @@
<value>BUT_write</value>
</data>
<data name="&gt;&gt;BUT_write.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
</data>
<data name="&gt;&gt;BUT_write.Parent" xml:space="preserve">
<value>panel5</value>
@ -583,7 +583,7 @@
<value>BUT_read</value>
</data>
<data name="&gt;&gt;BUT_read.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
</data>
<data name="&gt;&gt;BUT_read.Parent" xml:space="preserve">
<value>panel5</value>
@ -610,7 +610,7 @@
<value>SaveFile</value>
</data>
<data name="&gt;&gt;SaveFile.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
</data>
<data name="&gt;&gt;SaveFile.Parent" xml:space="preserve">
<value>panel5</value>
@ -637,7 +637,7 @@
<value>BUT_loadwpfile</value>
</data>
<data name="&gt;&gt;BUT_loadwpfile.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
</data>
<data name="&gt;&gt;BUT_loadwpfile.Parent" xml:space="preserve">
<value>panel5</value>
@ -1261,7 +1261,7 @@
<value>BUT_loadkml</value>
</data>
<data name="&gt;&gt;BUT_loadkml.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
</data>
<data name="&gt;&gt;BUT_loadkml.Parent" xml:space="preserve">
<value>panelWaypoints</value>
@ -1291,7 +1291,7 @@
<value>BUT_zoomto</value>
</data>
<data name="&gt;&gt;BUT_zoomto.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
</data>
<data name="&gt;&gt;BUT_zoomto.Parent" xml:space="preserve">
<value>panelWaypoints</value>
@ -1321,7 +1321,7 @@
<value>BUT_Camera</value>
</data>
<data name="&gt;&gt;BUT_Camera.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
</data>
<data name="&gt;&gt;BUT_Camera.Parent" xml:space="preserve">
<value>panelWaypoints</value>
@ -1351,7 +1351,7 @@
<value>BUT_grid</value>
</data>
<data name="&gt;&gt;BUT_grid.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
</data>
<data name="&gt;&gt;BUT_grid.Parent" xml:space="preserve">
<value>panelWaypoints</value>
@ -1381,7 +1381,7 @@
<value>BUT_Prefetch</value>
</data>
<data name="&gt;&gt;BUT_Prefetch.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
</data>
<data name="&gt;&gt;BUT_Prefetch.Parent" xml:space="preserve">
<value>panelWaypoints</value>
@ -1411,7 +1411,7 @@
<value>button1</value>
</data>
<data name="&gt;&gt;button1.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
</data>
<data name="&gt;&gt;button1.Parent" xml:space="preserve">
<value>panelWaypoints</value>
@ -1441,7 +1441,7 @@
<value>BUT_Add</value>
</data>
<data name="&gt;&gt;BUT_Add.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
</data>
<data name="&gt;&gt;BUT_Add.Parent" xml:space="preserve">
<value>panelWaypoints</value>

View File

@ -31,7 +31,7 @@
System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(Help));
this.richTextBox1 = new System.Windows.Forms.RichTextBox();
this.CHK_showconsole = new System.Windows.Forms.CheckBox();
this.BUT_updatecheck = new ArdupilotMega.MyButton();
this.BUT_updatecheck = new ArdupilotMega.Controls.MyButton();
this.SuspendLayout();
//
// richTextBox1
@ -71,7 +71,7 @@
#endregion
private System.Windows.Forms.RichTextBox richTextBox1;
private MyButton BUT_updatecheck;
private ArdupilotMega.Controls.MyButton BUT_updatecheck;
private System.Windows.Forms.CheckBox CHK_showconsole;
}

View File

@ -196,7 +196,7 @@
<value>BUT_updatecheck</value>
</data>
<data name="&gt;&gt;BUT_updatecheck.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
</data>
<data name="&gt;&gt;BUT_updatecheck.Parent" xml:space="preserve">
<value>$this</value>

View File

@ -34,81 +34,81 @@
this.CHKREV_pitch = new System.Windows.Forms.CheckBox();
this.CHKREV_rudder = new System.Windows.Forms.CheckBox();
this.GPSrate = new System.Windows.Forms.ComboBox();
this.ConnectComPort = new ArdupilotMega.MyButton();
this.ConnectComPort = new ArdupilotMega.Controls.MyButton();
this.OutputLog = new System.Windows.Forms.RichTextBox();
this.TXT_roll = new ArdupilotMega.MyLabel();
this.TXT_pitch = new ArdupilotMega.MyLabel();
this.TXT_heading = new ArdupilotMega.MyLabel();
this.TXT_wpdist = new ArdupilotMega.MyLabel();
this.TXT_roll = new ArdupilotMega.Controls.MyLabel();
this.TXT_pitch = new ArdupilotMega.Controls.MyLabel();
this.TXT_heading = new ArdupilotMega.Controls.MyLabel();
this.TXT_wpdist = new ArdupilotMega.Controls.MyLabel();
this.currentStateBindingSource = new System.Windows.Forms.BindingSource(this.components);
this.TXT_bererror = new ArdupilotMega.MyLabel();
this.TXT_alterror = new ArdupilotMega.MyLabel();
this.TXT_lat = new ArdupilotMega.MyLabel();
this.TXT_long = new ArdupilotMega.MyLabel();
this.TXT_alt = new ArdupilotMega.MyLabel();
this.SaveSettings = new ArdupilotMega.MyButton();
this.TXT_bererror = new ArdupilotMega.Controls.MyLabel();
this.TXT_alterror = new ArdupilotMega.Controls.MyLabel();
this.TXT_lat = new ArdupilotMega.Controls.MyLabel();
this.TXT_long = new ArdupilotMega.Controls.MyLabel();
this.TXT_alt = new ArdupilotMega.Controls.MyLabel();
this.SaveSettings = new ArdupilotMega.Controls.MyButton();
this.RAD_softXplanes = new System.Windows.Forms.RadioButton();
this.RAD_softFlightGear = new System.Windows.Forms.RadioButton();
this.TXT_servoroll = new ArdupilotMega.MyLabel();
this.TXT_servopitch = new ArdupilotMega.MyLabel();
this.TXT_servorudder = new ArdupilotMega.MyLabel();
this.TXT_servothrottle = new ArdupilotMega.MyLabel();
this.TXT_servoroll = new ArdupilotMega.Controls.MyLabel();
this.TXT_servopitch = new ArdupilotMega.Controls.MyLabel();
this.TXT_servorudder = new ArdupilotMega.Controls.MyLabel();
this.TXT_servothrottle = new ArdupilotMega.Controls.MyLabel();
this.panel1 = new System.Windows.Forms.Panel();
this.label4 = new ArdupilotMega.MyLabel();
this.label3 = new ArdupilotMega.MyLabel();
this.label2 = new ArdupilotMega.MyLabel();
this.label1 = new ArdupilotMega.MyLabel();
this.label4 = new ArdupilotMega.Controls.MyLabel();
this.label3 = new ArdupilotMega.Controls.MyLabel();
this.label2 = new ArdupilotMega.Controls.MyLabel();
this.label1 = new ArdupilotMega.Controls.MyLabel();
this.panel2 = new System.Windows.Forms.Panel();
this.label30 = new ArdupilotMega.MyLabel();
this.TXT_yaw = new ArdupilotMega.MyLabel();
this.label11 = new ArdupilotMega.MyLabel();
this.label7 = new ArdupilotMega.MyLabel();
this.label6 = new ArdupilotMega.MyLabel();
this.label5 = new ArdupilotMega.MyLabel();
this.label8 = new ArdupilotMega.MyLabel();
this.label9 = new ArdupilotMega.MyLabel();
this.label10 = new ArdupilotMega.MyLabel();
this.label30 = new ArdupilotMega.Controls.MyLabel();
this.TXT_yaw = new ArdupilotMega.Controls.MyLabel();
this.label11 = new ArdupilotMega.Controls.MyLabel();
this.label7 = new ArdupilotMega.Controls.MyLabel();
this.label6 = new ArdupilotMega.Controls.MyLabel();
this.label5 = new ArdupilotMega.Controls.MyLabel();
this.label8 = new ArdupilotMega.Controls.MyLabel();
this.label9 = new ArdupilotMega.Controls.MyLabel();
this.label10 = new ArdupilotMega.Controls.MyLabel();
this.panel3 = new System.Windows.Forms.Panel();
this.label16 = new ArdupilotMega.MyLabel();
this.label15 = new ArdupilotMega.MyLabel();
this.label14 = new ArdupilotMega.MyLabel();
this.label13 = new ArdupilotMega.MyLabel();
this.label12 = new ArdupilotMega.MyLabel();
this.label16 = new ArdupilotMega.Controls.MyLabel();
this.label15 = new ArdupilotMega.Controls.MyLabel();
this.label14 = new ArdupilotMega.Controls.MyLabel();
this.label13 = new ArdupilotMega.Controls.MyLabel();
this.label12 = new ArdupilotMega.Controls.MyLabel();
this.panel4 = new System.Windows.Forms.Panel();
this.label20 = new ArdupilotMega.MyLabel();
this.label19 = new ArdupilotMega.MyLabel();
this.TXT_control_mode = new ArdupilotMega.MyLabel();
this.TXT_WP = new ArdupilotMega.MyLabel();
this.label18 = new ArdupilotMega.MyLabel();
this.label17 = new ArdupilotMega.MyLabel();
this.label20 = new ArdupilotMega.Controls.MyLabel();
this.label19 = new ArdupilotMega.Controls.MyLabel();
this.TXT_control_mode = new ArdupilotMega.Controls.MyLabel();
this.TXT_WP = new ArdupilotMega.Controls.MyLabel();
this.label18 = new ArdupilotMega.Controls.MyLabel();
this.label17 = new ArdupilotMega.Controls.MyLabel();
this.panel5 = new System.Windows.Forms.Panel();
this.zg1 = new ZedGraph.ZedGraphControl();
this.timer_servo_graph = new System.Windows.Forms.Timer(this.components);
this.panel6 = new System.Windows.Forms.Panel();
this.label28 = new ArdupilotMega.MyLabel();
this.label29 = new ArdupilotMega.MyLabel();
this.label27 = new ArdupilotMega.MyLabel();
this.label25 = new ArdupilotMega.MyLabel();
this.label28 = new ArdupilotMega.Controls.MyLabel();
this.label29 = new ArdupilotMega.Controls.MyLabel();
this.label27 = new ArdupilotMega.Controls.MyLabel();
this.label25 = new ArdupilotMega.Controls.MyLabel();
this.TXT_throttlegain = new System.Windows.Forms.TextBox();
this.label24 = new ArdupilotMega.MyLabel();
this.label23 = new ArdupilotMega.MyLabel();
this.label22 = new ArdupilotMega.MyLabel();
this.label21 = new ArdupilotMega.MyLabel();
this.label24 = new ArdupilotMega.Controls.MyLabel();
this.label23 = new ArdupilotMega.Controls.MyLabel();
this.label22 = new ArdupilotMega.Controls.MyLabel();
this.label21 = new ArdupilotMega.Controls.MyLabel();
this.TXT_ruddergain = new System.Windows.Forms.TextBox();
this.TXT_pitchgain = new System.Windows.Forms.TextBox();
this.TXT_rollgain = new System.Windows.Forms.TextBox();
this.label26 = new ArdupilotMega.MyLabel();
this.label26 = new ArdupilotMega.Controls.MyLabel();
this.CHKdisplayall = new System.Windows.Forms.CheckBox();
this.CHKgraphroll = new System.Windows.Forms.CheckBox();
this.CHKgraphpitch = new System.Windows.Forms.CheckBox();
this.CHKgraphrudder = new System.Windows.Forms.CheckBox();
this.CHKgraphthrottle = new System.Windows.Forms.CheckBox();
this.but_advsettings = new ArdupilotMega.MyButton();
this.but_advsettings = new ArdupilotMega.Controls.MyButton();
this.chkSensor = new System.Windows.Forms.CheckBox();
this.CHK_quad = new System.Windows.Forms.CheckBox();
this.BUT_startfgquad = new ArdupilotMega.MyButton();
this.BUT_startfgplane = new ArdupilotMega.MyButton();
this.BUT_startxplane = new ArdupilotMega.MyButton();
this.BUT_startfgquad = new ArdupilotMega.Controls.MyButton();
this.BUT_startfgplane = new ArdupilotMega.Controls.MyButton();
this.BUT_startxplane = new ArdupilotMega.Controls.MyButton();
this.CHK_heli = new System.Windows.Forms.CheckBox();
this.RAD_aerosimrc = new System.Windows.Forms.RadioButton();
this.toolTip1 = new System.Windows.Forms.ToolTip(this.components);
@ -763,81 +763,81 @@
private System.Windows.Forms.CheckBox CHKREV_pitch;
private System.Windows.Forms.CheckBox CHKREV_rudder;
private System.Windows.Forms.ComboBox GPSrate;
private MyButton ConnectComPort;
private ArdupilotMega.Controls.MyButton ConnectComPort;
private System.Windows.Forms.RichTextBox OutputLog;
private ArdupilotMega.MyLabel TXT_roll;
private ArdupilotMega.MyLabel TXT_pitch;
private ArdupilotMega.MyLabel TXT_heading;
private ArdupilotMega.MyLabel TXT_wpdist;
private ArdupilotMega.MyLabel TXT_bererror;
private ArdupilotMega.MyLabel TXT_alterror;
private ArdupilotMega.MyLabel TXT_lat;
private ArdupilotMega.MyLabel TXT_long;
private ArdupilotMega.MyLabel TXT_alt;
private MyButton SaveSettings;
private ArdupilotMega.Controls.MyLabel TXT_roll;
private ArdupilotMega.Controls.MyLabel TXT_pitch;
private ArdupilotMega.Controls.MyLabel TXT_heading;
private ArdupilotMega.Controls.MyLabel TXT_wpdist;
private ArdupilotMega.Controls.MyLabel TXT_bererror;
private ArdupilotMega.Controls.MyLabel TXT_alterror;
private ArdupilotMega.Controls.MyLabel TXT_lat;
private ArdupilotMega.Controls.MyLabel TXT_long;
private ArdupilotMega.Controls.MyLabel TXT_alt;
private ArdupilotMega.Controls.MyButton SaveSettings;
private System.Windows.Forms.RadioButton RAD_softXplanes;
private System.Windows.Forms.RadioButton RAD_softFlightGear;
private ArdupilotMega.MyLabel TXT_servoroll;
private ArdupilotMega.MyLabel TXT_servopitch;
private ArdupilotMega.MyLabel TXT_servorudder;
private ArdupilotMega.MyLabel TXT_servothrottle;
private ArdupilotMega.Controls.MyLabel TXT_servoroll;
private ArdupilotMega.Controls.MyLabel TXT_servopitch;
private ArdupilotMega.Controls.MyLabel TXT_servorudder;
private ArdupilotMega.Controls.MyLabel TXT_servothrottle;
private System.Windows.Forms.Panel panel1;
private ArdupilotMega.MyLabel label3;
private ArdupilotMega.MyLabel label2;
private ArdupilotMega.MyLabel label1;
private ArdupilotMega.Controls.MyLabel label3;
private ArdupilotMega.Controls.MyLabel label2;
private ArdupilotMega.Controls.MyLabel label1;
private System.Windows.Forms.Panel panel2;
private ArdupilotMega.MyLabel label4;
private ArdupilotMega.MyLabel label10;
private ArdupilotMega.MyLabel label9;
private ArdupilotMega.MyLabel label8;
private ArdupilotMega.MyLabel label7;
private ArdupilotMega.MyLabel label6;
private ArdupilotMega.MyLabel label5;
private ArdupilotMega.MyLabel label11;
private ArdupilotMega.Controls.MyLabel label4;
private ArdupilotMega.Controls.MyLabel label10;
private ArdupilotMega.Controls.MyLabel label9;
private ArdupilotMega.Controls.MyLabel label8;
private ArdupilotMega.Controls.MyLabel label7;
private ArdupilotMega.Controls.MyLabel label6;
private ArdupilotMega.Controls.MyLabel label5;
private ArdupilotMega.Controls.MyLabel label11;
private System.Windows.Forms.Panel panel3;
private ArdupilotMega.MyLabel label16;
private ArdupilotMega.MyLabel label15;
private ArdupilotMega.MyLabel label14;
private ArdupilotMega.MyLabel label13;
private ArdupilotMega.MyLabel label12;
private ArdupilotMega.Controls.MyLabel label16;
private ArdupilotMega.Controls.MyLabel label15;
private ArdupilotMega.Controls.MyLabel label14;
private ArdupilotMega.Controls.MyLabel label13;
private ArdupilotMega.Controls.MyLabel label12;
private System.Windows.Forms.Panel panel4;
private ArdupilotMega.MyLabel label17;
private ArdupilotMega.MyLabel TXT_WP;
private ArdupilotMega.MyLabel label18;
private ArdupilotMega.Controls.MyLabel label17;
private ArdupilotMega.Controls.MyLabel TXT_WP;
private ArdupilotMega.Controls.MyLabel label18;
private System.Windows.Forms.Panel panel5;
private ArdupilotMega.MyLabel label20;
private ArdupilotMega.MyLabel label19;
private ArdupilotMega.MyLabel TXT_control_mode;
private ArdupilotMega.Controls.MyLabel label20;
private ArdupilotMega.Controls.MyLabel label19;
private ArdupilotMega.Controls.MyLabel TXT_control_mode;
private ZedGraph.ZedGraphControl zg1;
private System.Windows.Forms.Timer timer_servo_graph;
private System.Windows.Forms.Panel panel6;
private System.Windows.Forms.TextBox TXT_ruddergain;
private System.Windows.Forms.TextBox TXT_pitchgain;
private System.Windows.Forms.TextBox TXT_rollgain;
private ArdupilotMega.MyLabel label24;
private ArdupilotMega.MyLabel label23;
private ArdupilotMega.MyLabel label22;
private ArdupilotMega.MyLabel label21;
private ArdupilotMega.MyLabel label25;
private ArdupilotMega.Controls.MyLabel label24;
private ArdupilotMega.Controls.MyLabel label23;
private ArdupilotMega.Controls.MyLabel label22;
private ArdupilotMega.Controls.MyLabel label21;
private ArdupilotMega.Controls.MyLabel label25;
private System.Windows.Forms.TextBox TXT_throttlegain;
private ArdupilotMega.MyLabel label28;
private ArdupilotMega.MyLabel label29;
private ArdupilotMega.MyLabel label27;
private ArdupilotMega.MyLabel label26;
private ArdupilotMega.Controls.MyLabel label28;
private ArdupilotMega.Controls.MyLabel label29;
private ArdupilotMega.Controls.MyLabel label27;
private ArdupilotMega.Controls.MyLabel label26;
private System.Windows.Forms.CheckBox CHKdisplayall;
private System.Windows.Forms.CheckBox CHKgraphroll;
private System.Windows.Forms.CheckBox CHKgraphpitch;
private System.Windows.Forms.CheckBox CHKgraphrudder;
private System.Windows.Forms.CheckBox CHKgraphthrottle;
private ArdupilotMega.MyLabel label30;
private ArdupilotMega.MyLabel TXT_yaw;
private MyButton but_advsettings;
private ArdupilotMega.Controls.MyLabel label30;
private ArdupilotMega.Controls.MyLabel TXT_yaw;
private ArdupilotMega.Controls.MyButton but_advsettings;
private System.Windows.Forms.CheckBox chkSensor;
private System.Windows.Forms.BindingSource currentStateBindingSource;
private System.Windows.Forms.CheckBox CHK_quad;
private MyButton BUT_startfgquad;
private MyButton BUT_startfgplane;
private MyButton BUT_startxplane;
private ArdupilotMega.Controls.MyButton BUT_startfgquad;
private ArdupilotMega.Controls.MyButton BUT_startfgplane;
private ArdupilotMega.Controls.MyButton BUT_startxplane;
private System.Windows.Forms.CheckBox CHK_heli;
private System.Windows.Forms.RadioButton RAD_aerosimrc;
private System.Windows.Forms.ToolTip toolTip1;

View File

@ -13,7 +13,7 @@ using log4net;
using ZedGraph; // Graphs
using ArdupilotMega;
using System.Reflection;
using ArdupilotMega.Controls;
using System.Drawing.Drawing2D;
// Written by Michael Oborne

View File

@ -261,7 +261,7 @@
<value>ConnectComPort</value>
</data>
<data name="&gt;&gt;ConnectComPort.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
</data>
<data name="&gt;&gt;ConnectComPort.Parent" xml:space="preserve">
<value>panel5</value>
@ -309,7 +309,7 @@
<value>TXT_roll</value>
</data>
<data name="&gt;&gt;TXT_roll.Type" xml:space="preserve">
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
<value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
</data>
<data name="&gt;&gt;TXT_roll.Parent" xml:space="preserve">
<value>panel2</value>
@ -330,7 +330,7 @@
<value>TXT_pitch</value>
</data>
<data name="&gt;&gt;TXT_pitch.Type" xml:space="preserve">
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
<value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
</data>
<data name="&gt;&gt;TXT_pitch.Parent" xml:space="preserve">
<value>panel2</value>
@ -351,7 +351,7 @@
<value>TXT_heading</value>
</data>
<data name="&gt;&gt;TXT_heading.Type" xml:space="preserve">
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
<value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
</data>
<data name="&gt;&gt;TXT_heading.Parent" xml:space="preserve">
<value>panel2</value>
@ -372,7 +372,7 @@
<value>TXT_wpdist</value>
</data>
<data name="&gt;&gt;TXT_wpdist.Type" xml:space="preserve">
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
<value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
</data>
<data name="&gt;&gt;TXT_wpdist.Parent" xml:space="preserve">
<value>panel4</value>
@ -396,7 +396,7 @@
<value>TXT_bererror</value>
</data>
<data name="&gt;&gt;TXT_bererror.Type" xml:space="preserve">
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
<value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
</data>
<data name="&gt;&gt;TXT_bererror.Parent" xml:space="preserve">
<value>panel4</value>
@ -417,7 +417,7 @@
<value>TXT_alterror</value>
</data>
<data name="&gt;&gt;TXT_alterror.Type" xml:space="preserve">
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
<value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
</data>
<data name="&gt;&gt;TXT_alterror.Parent" xml:space="preserve">
<value>panel4</value>
@ -438,7 +438,7 @@
<value>TXT_lat</value>
</data>
<data name="&gt;&gt;TXT_lat.Type" xml:space="preserve">
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
<value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
</data>
<data name="&gt;&gt;TXT_lat.Parent" xml:space="preserve">
<value>panel1</value>
@ -459,7 +459,7 @@
<value>TXT_long</value>
</data>
<data name="&gt;&gt;TXT_long.Type" xml:space="preserve">
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
<value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
</data>
<data name="&gt;&gt;TXT_long.Parent" xml:space="preserve">
<value>panel1</value>
@ -480,7 +480,7 @@
<value>TXT_alt</value>
</data>
<data name="&gt;&gt;TXT_alt.Type" xml:space="preserve">
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
<value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
</data>
<data name="&gt;&gt;TXT_alt.Parent" xml:space="preserve">
<value>panel1</value>
@ -504,7 +504,7 @@
<value>SaveSettings</value>
</data>
<data name="&gt;&gt;SaveSettings.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
</data>
<data name="&gt;&gt;SaveSettings.Parent" xml:space="preserve">
<value>$this</value>
@ -588,7 +588,7 @@
<value>TXT_servoroll</value>
</data>
<data name="&gt;&gt;TXT_servoroll.Type" xml:space="preserve">
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
<value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
</data>
<data name="&gt;&gt;TXT_servoroll.Parent" xml:space="preserve">
<value>panel3</value>
@ -609,7 +609,7 @@
<value>TXT_servopitch</value>
</data>
<data name="&gt;&gt;TXT_servopitch.Type" xml:space="preserve">
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
<value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
</data>
<data name="&gt;&gt;TXT_servopitch.Parent" xml:space="preserve">
<value>panel3</value>
@ -630,7 +630,7 @@
<value>TXT_servorudder</value>
</data>
<data name="&gt;&gt;TXT_servorudder.Type" xml:space="preserve">
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
<value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
</data>
<data name="&gt;&gt;TXT_servorudder.Parent" xml:space="preserve">
<value>panel3</value>
@ -651,7 +651,7 @@
<value>TXT_servothrottle</value>
</data>
<data name="&gt;&gt;TXT_servothrottle.Type" xml:space="preserve">
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
<value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
</data>
<data name="&gt;&gt;TXT_servothrottle.Parent" xml:space="preserve">
<value>panel3</value>
@ -675,7 +675,7 @@
<value>label4</value>
</data>
<data name="&gt;&gt;label4.Type" xml:space="preserve">
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
<value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
</data>
<data name="&gt;&gt;label4.Parent" xml:space="preserve">
<value>panel1</value>
@ -699,7 +699,7 @@
<value>label3</value>
</data>
<data name="&gt;&gt;label3.Type" xml:space="preserve">
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
<value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
</data>
<data name="&gt;&gt;label3.Parent" xml:space="preserve">
<value>panel1</value>
@ -723,7 +723,7 @@
<value>label2</value>
</data>
<data name="&gt;&gt;label2.Type" xml:space="preserve">
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
<value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
</data>
<data name="&gt;&gt;label2.Parent" xml:space="preserve">
<value>panel1</value>
@ -747,7 +747,7 @@
<value>label1</value>
</data>
<data name="&gt;&gt;label1.Type" xml:space="preserve">
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
<value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
</data>
<data name="&gt;&gt;label1.Parent" xml:space="preserve">
<value>panel1</value>
@ -792,7 +792,7 @@
<value>label30</value>
</data>
<data name="&gt;&gt;label30.Type" xml:space="preserve">
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
<value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
</data>
<data name="&gt;&gt;label30.Parent" xml:space="preserve">
<value>panel2</value>
@ -813,7 +813,7 @@
<value>TXT_yaw</value>
</data>
<data name="&gt;&gt;TXT_yaw.Type" xml:space="preserve">
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
<value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
</data>
<data name="&gt;&gt;TXT_yaw.Parent" xml:space="preserve">
<value>panel2</value>
@ -837,7 +837,7 @@
<value>label11</value>
</data>
<data name="&gt;&gt;label11.Type" xml:space="preserve">
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
<value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
</data>
<data name="&gt;&gt;label11.Parent" xml:space="preserve">
<value>panel2</value>
@ -861,7 +861,7 @@
<value>label7</value>
</data>
<data name="&gt;&gt;label7.Type" xml:space="preserve">
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
<value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
</data>
<data name="&gt;&gt;label7.Parent" xml:space="preserve">
<value>panel2</value>
@ -885,7 +885,7 @@
<value>label6</value>
</data>
<data name="&gt;&gt;label6.Type" xml:space="preserve">
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
<value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
</data>
<data name="&gt;&gt;label6.Parent" xml:space="preserve">
<value>panel2</value>
@ -909,7 +909,7 @@
<value>label5</value>
</data>
<data name="&gt;&gt;label5.Type" xml:space="preserve">
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
<value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
</data>
<data name="&gt;&gt;label5.Parent" xml:space="preserve">
<value>panel2</value>
@ -954,7 +954,7 @@
<value>label8</value>
</data>
<data name="&gt;&gt;label8.Type" xml:space="preserve">
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
<value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
</data>
<data name="&gt;&gt;label8.Parent" xml:space="preserve">
<value>panel4</value>
@ -978,7 +978,7 @@
<value>label9</value>
</data>
<data name="&gt;&gt;label9.Type" xml:space="preserve">
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
<value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
</data>
<data name="&gt;&gt;label9.Parent" xml:space="preserve">
<value>panel4</value>
@ -1002,7 +1002,7 @@
<value>label10</value>
</data>
<data name="&gt;&gt;label10.Type" xml:space="preserve">
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
<value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
</data>
<data name="&gt;&gt;label10.Parent" xml:space="preserve">
<value>panel4</value>
@ -1026,7 +1026,7 @@
<value>label16</value>
</data>
<data name="&gt;&gt;label16.Type" xml:space="preserve">
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
<value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
</data>
<data name="&gt;&gt;label16.Parent" xml:space="preserve">
<value>panel3</value>
@ -1050,7 +1050,7 @@
<value>label15</value>
</data>
<data name="&gt;&gt;label15.Type" xml:space="preserve">
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
<value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
</data>
<data name="&gt;&gt;label15.Parent" xml:space="preserve">
<value>panel3</value>
@ -1074,7 +1074,7 @@
<value>label14</value>
</data>
<data name="&gt;&gt;label14.Type" xml:space="preserve">
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
<value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
</data>
<data name="&gt;&gt;label14.Parent" xml:space="preserve">
<value>panel3</value>
@ -1098,7 +1098,7 @@
<value>label13</value>
</data>
<data name="&gt;&gt;label13.Type" xml:space="preserve">
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
<value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
</data>
<data name="&gt;&gt;label13.Parent" xml:space="preserve">
<value>panel3</value>
@ -1122,7 +1122,7 @@
<value>label12</value>
</data>
<data name="&gt;&gt;label12.Type" xml:space="preserve">
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
<value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
</data>
<data name="&gt;&gt;label12.Parent" xml:space="preserve">
<value>panel3</value>
@ -1167,7 +1167,7 @@
<value>label20</value>
</data>
<data name="&gt;&gt;label20.Type" xml:space="preserve">
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
<value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
</data>
<data name="&gt;&gt;label20.Parent" xml:space="preserve">
<value>panel4</value>
@ -1191,7 +1191,7 @@
<value>label19</value>
</data>
<data name="&gt;&gt;label19.Type" xml:space="preserve">
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
<value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
</data>
<data name="&gt;&gt;label19.Parent" xml:space="preserve">
<value>panel4</value>
@ -1212,7 +1212,7 @@
<value>TXT_control_mode</value>
</data>
<data name="&gt;&gt;TXT_control_mode.Type" xml:space="preserve">
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
<value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
</data>
<data name="&gt;&gt;TXT_control_mode.Parent" xml:space="preserve">
<value>panel4</value>
@ -1233,7 +1233,7 @@
<value>TXT_WP</value>
</data>
<data name="&gt;&gt;TXT_WP.Type" xml:space="preserve">
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
<value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
</data>
<data name="&gt;&gt;TXT_WP.Parent" xml:space="preserve">
<value>panel4</value>
@ -1257,7 +1257,7 @@
<value>label18</value>
</data>
<data name="&gt;&gt;label18.Type" xml:space="preserve">
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
<value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
</data>
<data name="&gt;&gt;label18.Parent" xml:space="preserve">
<value>panel4</value>
@ -1302,7 +1302,7 @@
<value>label17</value>
</data>
<data name="&gt;&gt;label17.Type" xml:space="preserve">
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
<value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
</data>
<data name="&gt;&gt;label17.Parent" xml:space="preserve">
<value>$this</value>
@ -1375,7 +1375,7 @@
<value>label28</value>
</data>
<data name="&gt;&gt;label28.Type" xml:space="preserve">
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
<value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
</data>
<data name="&gt;&gt;label28.Parent" xml:space="preserve">
<value>panel6</value>
@ -1399,7 +1399,7 @@
<value>label29</value>
</data>
<data name="&gt;&gt;label29.Type" xml:space="preserve">
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
<value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
</data>
<data name="&gt;&gt;label29.Parent" xml:space="preserve">
<value>panel6</value>
@ -1423,7 +1423,7 @@
<value>label27</value>
</data>
<data name="&gt;&gt;label27.Type" xml:space="preserve">
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
<value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
</data>
<data name="&gt;&gt;label27.Parent" xml:space="preserve">
<value>panel6</value>
@ -1447,7 +1447,7 @@
<value>label25</value>
</data>
<data name="&gt;&gt;label25.Type" xml:space="preserve">
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
<value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
</data>
<data name="&gt;&gt;label25.Parent" xml:space="preserve">
<value>panel6</value>
@ -1495,7 +1495,7 @@
<value>label24</value>
</data>
<data name="&gt;&gt;label24.Type" xml:space="preserve">
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
<value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
</data>
<data name="&gt;&gt;label24.Parent" xml:space="preserve">
<value>panel6</value>
@ -1519,7 +1519,7 @@
<value>label23</value>
</data>
<data name="&gt;&gt;label23.Type" xml:space="preserve">
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
<value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
</data>
<data name="&gt;&gt;label23.Parent" xml:space="preserve">
<value>panel6</value>
@ -1543,7 +1543,7 @@
<value>label22</value>
</data>
<data name="&gt;&gt;label22.Type" xml:space="preserve">
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
<value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
</data>
<data name="&gt;&gt;label22.Parent" xml:space="preserve">
<value>panel6</value>
@ -1567,7 +1567,7 @@
<value>label21</value>
</data>
<data name="&gt;&gt;label21.Type" xml:space="preserve">
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
<value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
</data>
<data name="&gt;&gt;label21.Parent" xml:space="preserve">
<value>panel6</value>
@ -1684,7 +1684,7 @@
<value>label26</value>
</data>
<data name="&gt;&gt;label26.Type" xml:space="preserve">
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
<value>ArdupilotMega.Controls.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
</data>
<data name="&gt;&gt;label26.Parent" xml:space="preserve">
<value>$this</value>
@ -1855,7 +1855,7 @@
<value>but_advsettings</value>
</data>
<data name="&gt;&gt;but_advsettings.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
</data>
<data name="&gt;&gt;but_advsettings.Parent" xml:space="preserve">
<value>$this</value>
@ -1939,7 +1939,7 @@
<value>BUT_startfgquad</value>
</data>
<data name="&gt;&gt;BUT_startfgquad.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
</data>
<data name="&gt;&gt;BUT_startfgquad.Parent" xml:space="preserve">
<value>$this</value>
@ -1966,7 +1966,7 @@
<value>BUT_startfgplane</value>
</data>
<data name="&gt;&gt;BUT_startfgplane.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
</data>
<data name="&gt;&gt;BUT_startfgplane.Parent" xml:space="preserve">
<value>$this</value>
@ -1993,7 +1993,7 @@
<value>BUT_startxplane</value>
</data>
<data name="&gt;&gt;BUT_startxplane.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
</data>
<data name="&gt;&gt;BUT_startxplane.Parent" xml:space="preserve">
<value>$this</value>

View File

@ -30,11 +30,11 @@
{
System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(Terminal));
this.TXT_terminal = new System.Windows.Forms.RichTextBox();
this.BUTsetupshow = new ArdupilotMega.MyButton();
this.BUTradiosetup = new ArdupilotMega.MyButton();
this.BUTtests = new ArdupilotMega.MyButton();
this.Logs = new ArdupilotMega.MyButton();
this.BUT_logbrowse = new ArdupilotMega.MyButton();
this.BUTsetupshow = new ArdupilotMega.Controls.MyButton();
this.BUTradiosetup = new ArdupilotMega.Controls.MyButton();
this.BUTtests = new ArdupilotMega.Controls.MyButton();
this.Logs = new ArdupilotMega.Controls.MyButton();
this.BUT_logbrowse = new ArdupilotMega.Controls.MyButton();
this.SuspendLayout();
//
// TXT_terminal
@ -101,10 +101,10 @@
#endregion
private System.Windows.Forms.RichTextBox TXT_terminal;
private MyButton BUTsetupshow;
private MyButton BUTradiosetup;
private MyButton BUTtests;
private MyButton Logs;
private MyButton BUT_logbrowse;
private ArdupilotMega.Controls.MyButton BUTsetupshow;
private ArdupilotMega.Controls.MyButton BUTradiosetup;
private ArdupilotMega.Controls.MyButton BUTtests;
private ArdupilotMega.Controls.MyButton Logs;
private ArdupilotMega.Controls.MyButton BUT_logbrowse;
}
}

View File

@ -8,6 +8,8 @@ using System.Text;
using System.Windows.Forms;
using ArdupilotMega;
using System.IO.Ports;
using ArdupilotMega.Comms;
namespace ArdupilotMega.GCSViews
{

View File

@ -166,7 +166,7 @@
<value>BUTsetupshow</value>
</data>
<data name="&gt;&gt;BUTsetupshow.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
</data>
<data name="&gt;&gt;BUTsetupshow.Parent" xml:space="preserve">
<value>$this</value>
@ -190,7 +190,7 @@
<value>BUTradiosetup</value>
</data>
<data name="&gt;&gt;BUTradiosetup.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
</data>
<data name="&gt;&gt;BUTradiosetup.Parent" xml:space="preserve">
<value>$this</value>
@ -214,7 +214,7 @@
<value>BUTtests</value>
</data>
<data name="&gt;&gt;BUTtests.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
</data>
<data name="&gt;&gt;BUTtests.Parent" xml:space="preserve">
<value>$this</value>
@ -238,7 +238,7 @@
<value>Logs</value>
</data>
<data name="&gt;&gt;Logs.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
</data>
<data name="&gt;&gt;Logs.Parent" xml:space="preserve">
<value>$this</value>
@ -262,7 +262,7 @@
<value>BUT_logbrowse</value>
</data>
<data name="&gt;&gt;BUT_logbrowse.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
</data>
<data name="&gt;&gt;BUT_logbrowse.Parent" xml:space="preserve">
<value>$this</value>

View File

@ -70,23 +70,23 @@
this.label13 = new System.Windows.Forms.Label();
this.expo_ch8 = new System.Windows.Forms.TextBox();
this.CMB_CH8 = new System.Windows.Forms.ComboBox();
this.BUT_detch8 = new ArdupilotMega.MyButton();
this.BUT_detch8 = new ArdupilotMega.Controls.MyButton();
this.horizontalProgressBar4 = new ArdupilotMega.HorizontalProgressBar();
this.BUT_detch4 = new ArdupilotMega.MyButton();
this.BUT_detch3 = new ArdupilotMega.MyButton();
this.BUT_detch2 = new ArdupilotMega.MyButton();
this.BUT_detch1 = new ArdupilotMega.MyButton();
this.BUT_enable = new ArdupilotMega.MyButton();
this.BUT_save = new ArdupilotMega.MyButton();
this.BUT_detch4 = new ArdupilotMega.Controls.MyButton();
this.BUT_detch3 = new ArdupilotMega.Controls.MyButton();
this.BUT_detch2 = new ArdupilotMega.Controls.MyButton();
this.BUT_detch1 = new ArdupilotMega.Controls.MyButton();
this.BUT_enable = new ArdupilotMega.Controls.MyButton();
this.BUT_save = new ArdupilotMega.Controls.MyButton();
this.progressBar4 = new ArdupilotMega.HorizontalProgressBar();
this.progressBar3 = new ArdupilotMega.HorizontalProgressBar();
this.progressBar2 = new ArdupilotMega.HorizontalProgressBar();
this.progressBar1 = new ArdupilotMega.HorizontalProgressBar();
this.BUT_detch5 = new ArdupilotMega.MyButton();
this.BUT_detch5 = new ArdupilotMega.Controls.MyButton();
this.horizontalProgressBar1 = new ArdupilotMega.HorizontalProgressBar();
this.BUT_detch6 = new ArdupilotMega.MyButton();
this.BUT_detch6 = new ArdupilotMega.Controls.MyButton();
this.horizontalProgressBar2 = new ArdupilotMega.HorizontalProgressBar();
this.BUT_detch7 = new ArdupilotMega.MyButton();
this.BUT_detch7 = new ArdupilotMega.Controls.MyButton();
this.horizontalProgressBar3 = new ArdupilotMega.HorizontalProgressBar();
this.SuspendLayout();
//
@ -625,38 +625,38 @@
private System.Windows.Forms.CheckBox revCH2;
private System.Windows.Forms.CheckBox revCH3;
private System.Windows.Forms.CheckBox revCH4;
private MyButton BUT_save;
private MyButton BUT_enable;
private ArdupilotMega.Controls.MyButton BUT_save;
private ArdupilotMega.Controls.MyButton BUT_enable;
private System.Windows.Forms.Label label5;
private System.Windows.Forms.Label label6;
private System.Windows.Forms.Label label7;
private System.Windows.Forms.Label label8;
private System.Windows.Forms.Label label9;
private System.Windows.Forms.Timer timer1;
private MyButton BUT_detch1;
private MyButton BUT_detch2;
private MyButton BUT_detch3;
private MyButton BUT_detch4;
private ArdupilotMega.Controls.MyButton BUT_detch1;
private ArdupilotMega.Controls.MyButton BUT_detch2;
private ArdupilotMega.Controls.MyButton BUT_detch3;
private ArdupilotMega.Controls.MyButton BUT_detch4;
private System.Windows.Forms.CheckBox CHK_elevons;
private MyButton BUT_detch5;
private ArdupilotMega.Controls.MyButton BUT_detch5;
private System.Windows.Forms.CheckBox revCH5;
private System.Windows.Forms.Label label10;
private System.Windows.Forms.TextBox expo_ch5;
private HorizontalProgressBar horizontalProgressBar1;
private System.Windows.Forms.ComboBox CMB_CH5;
private MyButton BUT_detch6;
private ArdupilotMega.Controls.MyButton BUT_detch6;
private System.Windows.Forms.CheckBox revCH6;
private System.Windows.Forms.Label label11;
private System.Windows.Forms.TextBox expo_ch6;
private HorizontalProgressBar horizontalProgressBar2;
private System.Windows.Forms.ComboBox CMB_CH6;
private MyButton BUT_detch7;
private ArdupilotMega.Controls.MyButton BUT_detch7;
private System.Windows.Forms.CheckBox revCH7;
private System.Windows.Forms.Label label12;
private System.Windows.Forms.TextBox expo_ch7;
private HorizontalProgressBar horizontalProgressBar3;
private System.Windows.Forms.ComboBox CMB_CH7;
private MyButton BUT_detch8;
private ArdupilotMega.Controls.MyButton BUT_detch8;
private System.Windows.Forms.CheckBox revCH8;
private System.Windows.Forms.Label label13;
private System.Windows.Forms.TextBox expo_ch8;

View File

@ -7,7 +7,8 @@ using System.Linq;
using System.Text;
using System.Windows.Forms;
using Microsoft.DirectX.DirectInput;
using ArdupilotMega.Controls;
using ArdupilotMega.Utilities;
namespace ArdupilotMega
@ -408,7 +409,7 @@ namespace ArdupilotMega
{
MyLabel lbl = new MyLabel();
ComboBox cmbbutton = new ComboBox();
MyButton mybut = new MyButton();
ArdupilotMega.Controls.MyButton mybut = new ArdupilotMega.Controls.MyButton();
HorizontalProgressBar hbar = new HorizontalProgressBar();
ComboBox cmbaction = new ComboBox();
@ -440,7 +441,11 @@ namespace ArdupilotMega
cmbaction.Location = new Point(hbar.Right + 5, y);
cmbaction.Size = new Size(100, 21);
cmbaction.DataSource = (Enum.GetValues(Common.getModes()));
cmbaction.DataSource = Common.getModesList();
cmbaction.ValueMember = "Key";
cmbaction.DisplayMember = "Value";
cmbaction.DropDownStyle = ComboBoxStyle.DropDownList;
cmbaction.Name = "cmbaction" + name;
if (MainV2.config["butaction" + name] != null)

View File

@ -1258,7 +1258,7 @@
<value>BUT_detch8</value>
</data>
<data name="&gt;&gt;BUT_detch8.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
</data>
<data name="&gt;&gt;BUT_detch8.Parent" xml:space="preserve">
<value>$this</value>
@ -1309,7 +1309,7 @@
<value>BUT_detch4</value>
</data>
<data name="&gt;&gt;BUT_detch4.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
</data>
<data name="&gt;&gt;BUT_detch4.Parent" xml:space="preserve">
<value>$this</value>
@ -1336,7 +1336,7 @@
<value>BUT_detch3</value>
</data>
<data name="&gt;&gt;BUT_detch3.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
</data>
<data name="&gt;&gt;BUT_detch3.Parent" xml:space="preserve">
<value>$this</value>
@ -1363,7 +1363,7 @@
<value>BUT_detch2</value>
</data>
<data name="&gt;&gt;BUT_detch2.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
</data>
<data name="&gt;&gt;BUT_detch2.Parent" xml:space="preserve">
<value>$this</value>
@ -1390,7 +1390,7 @@
<value>BUT_detch1</value>
</data>
<data name="&gt;&gt;BUT_detch1.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
</data>
<data name="&gt;&gt;BUT_detch1.Parent" xml:space="preserve">
<value>$this</value>
@ -1417,7 +1417,7 @@
<value>BUT_enable</value>
</data>
<data name="&gt;&gt;BUT_enable.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
</data>
<data name="&gt;&gt;BUT_enable.Parent" xml:space="preserve">
<value>$this</value>
@ -1444,7 +1444,7 @@
<value>BUT_save</value>
</data>
<data name="&gt;&gt;BUT_save.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
</data>
<data name="&gt;&gt;BUT_save.Parent" xml:space="preserve">
<value>$this</value>
@ -1567,7 +1567,7 @@
<value>BUT_detch5</value>
</data>
<data name="&gt;&gt;BUT_detch5.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
</data>
<data name="&gt;&gt;BUT_detch5.Parent" xml:space="preserve">
<value>$this</value>
@ -1618,7 +1618,7 @@
<value>BUT_detch6</value>
</data>
<data name="&gt;&gt;BUT_detch6.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
</data>
<data name="&gt;&gt;BUT_detch6.Parent" xml:space="preserve">
<value>$this</value>
@ -1669,7 +1669,7 @@
<value>BUT_detch7</value>
</data>
<data name="&gt;&gt;BUT_detch7.Type" xml:space="preserve">
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
</data>
<data name="&gt;&gt;BUT_detch7.Parent" xml:space="preserve">
<value>$this</value>

View File

@ -30,13 +30,13 @@
{
System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(Log));
this.TXT_seriallog = new System.Windows.Forms.TextBox();
this.BUT_DLall = new ArdupilotMega.MyButton();
this.BUT_DLthese = new ArdupilotMega.MyButton();
this.BUT_clearlogs = new ArdupilotMega.MyButton();
this.BUT_DLall = new ArdupilotMega.Controls.MyButton();
this.BUT_DLthese = new ArdupilotMega.Controls.MyButton();
this.BUT_clearlogs = new ArdupilotMega.Controls.MyButton();
this.CHK_logs = new System.Windows.Forms.CheckedListBox();
this.TXT_status = new System.Windows.Forms.TextBox();
this.BUT_redokml = new ArdupilotMega.MyButton();
this.BUT_firstperson = new ArdupilotMega.MyButton();
this.BUT_redokml = new ArdupilotMega.Controls.MyButton();
this.BUT_firstperson = new ArdupilotMega.Controls.MyButton();
this.SuspendLayout();
//
// TXT_seriallog
@ -114,13 +114,13 @@
#endregion
private MyButton BUT_DLall;
private MyButton BUT_DLthese;
private MyButton BUT_clearlogs;
private ArdupilotMega.Controls.MyButton BUT_DLall;
private ArdupilotMega.Controls.MyButton BUT_DLthese;
private ArdupilotMega.Controls.MyButton BUT_clearlogs;
private System.Windows.Forms.CheckedListBox CHK_logs;
private System.Windows.Forms.TextBox TXT_status;
private MyButton BUT_redokml;
private ArdupilotMega.Controls.MyButton BUT_redokml;
private System.Windows.Forms.TextBox TXT_seriallog;
private MyButton BUT_firstperson;
private ArdupilotMega.Controls.MyButton BUT_firstperson;
}
}

Some files were not shown because too many files have changed in this diff Show More