diff --git a/ArduCopter/APM_Config.h b/ArduCopter/APM_Config.h index a92afc096343a53153befb5fab314a44c83706f3..9a9aaec63fd734b9dd7a148aef3841fe5033e7c4 100644 --- a/ArduCopter/APM_Config.h +++ b/ArduCopter/APM_Config.h @@ -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 diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde index 19b34a608227446c6ae32fa7cd66ec39ef3548e0..319f9415668c709f773fe28f7638dd63e30c0635 100644 --- a/ArduCopter/ArduCopter.pde +++ b/ArduCopter/ArduCopter.pde @@ -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" diff --git a/ArduCopter/GCS.h b/ArduCopter/GCS.h index 607fe197dd03b4590b11b3d65bf26a8621ca9c9b..c10a7e0d670f6620d47ed5e470c19e7baa3aef7a 100644 --- a/ArduCopter/GCS.h +++ b/ArduCopter/GCS.h @@ -8,7 +8,6 @@ #include <FastSerial.h> #include <AP_Common.h> -#include <GCS_MAVLink.h> #include <GPS.h> #include <Stream.h> #include <stdint.h> diff --git a/ArduCopter/GCS_Mavlink.pde b/ArduCopter/GCS_Mavlink.pde index f6692591d9eb966361b2cee9d47a5e93527357f9..8c9d2b2ba678c118c407c7650ed229d46c5d20ef 100644 --- a/ArduCopter/GCS_Mavlink.pde +++ b/ArduCopter/GCS_Mavlink.pde @@ -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, + MAV_TYPE_QUADROTOR, + MAV_AUTOPILOT_ARDUPILOTMEGA, + base_mode, + custom_mode, + system_status); +#else // MAVLINK10 mavlink_msg_heartbeat_send( chan, - 2 /*mavlink_system.type*/, //MAV_TYPE_QUADROTOR + 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 +} diff --git a/ArduCopter/Makefile b/ArduCopter/Makefile index 39784e4912c80665371647802209744742d810a7..2beb16563a9bd70b479f5c120bde6f2c5e1418c7 100644 --- a/ArduCopter/Makefile +++ b/ArduCopter/Makefile @@ -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 diff --git a/ArduCopter/defines.h b/ArduCopter/defines.h index 123d843a13320742443a9492775c6c1ae53aa6c1..69803555e7d6a348ee41aa16ae4c21c3f46c352b 100644 --- a/ArduCopter/defines.h +++ b/ArduCopter/defines.h @@ -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 diff --git a/ArduPlane/APM_Config.h b/ArduPlane/APM_Config.h index 18b5794ca717d6b5cc1e6015c8608ff5ee1b7329..36e10ac9d19d60833e47159808076ad82e63ed42 100644 --- a/ArduPlane/APM_Config.h +++ b/ArduPlane/APM_Config.h @@ -28,3 +28,6 @@ */ +// use this to enable the new MAVLink 1.0 protocol, instead of the +// older 0.9 protocol +// #define MAVLINK10 ENABLED diff --git a/ArduPlane/ArduPlane.pde b/ArduPlane/ArduPlane.pde index 7740128199c7ad9c6b3ccf411a93daa80dc1aca8..fcf4af17bf4f152444315a572ce67f839d578158 100644 --- a/ArduPlane/ArduPlane.pde +++ b/ArduPlane/ArduPlane.pde @@ -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" diff --git a/ArduPlane/GCS.h b/ArduPlane/GCS.h index 607fe197dd03b4590b11b3d65bf26a8621ca9c9b..c10a7e0d670f6620d47ed5e470c19e7baa3aef7a 100644 --- a/ArduPlane/GCS.h +++ b/ArduPlane/GCS.h @@ -8,7 +8,6 @@ #include <FastSerial.h> #include <AP_Common.h> -#include <GCS_MAVLink.h> #include <GPS.h> #include <Stream.h> #include <stdint.h> diff --git a/ArduPlane/GCS_Mavlink.pde b/ArduPlane/GCS_Mavlink.pde index df31a18511bd46725c00cda61d92750a7aeb1962..c1313c37ba9ae53ebd6925fd91ccad73caf677ea 100644 --- a/ArduPlane/GCS_Mavlink.pde +++ b/ArduPlane/GCS_Mavlink.pde @@ -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 +} diff --git a/ArduPlane/Makefile b/ArduPlane/Makefile index 04b4166c39bd0b8e5941ca6b739f400ea77577c7..d8ed558b997538b878f88c337ec8ba03cd12268b 100644 --- a/ArduPlane/Makefile +++ b/ArduPlane/Makefile @@ -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" diff --git a/ArduPlane/defines.h b/ArduPlane/defines.h index 9144bf3cfdd05c9800c8ade252f22d79fca02d7a..f88576b2b8daca3b119c2c60d17b7914c5af7222 100644 --- a/ArduPlane/defines.h +++ b/ArduPlane/defines.h @@ -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 diff --git a/Tools/ArdupilotMegaPlanner/Antenna/ArduTracker.cs b/Tools/ArdupilotMegaPlanner/Antenna/ArduTracker.cs index 8665324335198a82d8f73963fc05c5e8dc526f7d..8b4fee9116c31c6b7c190186c110292dc163aee0 100644 --- a/Tools/ArdupilotMegaPlanner/Antenna/ArduTracker.cs +++ b/Tools/ArdupilotMegaPlanner/Antenna/ArduTracker.cs @@ -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> diff --git a/Tools/ArdupilotMegaPlanner/Antenna/ITrackerOutput.cs b/Tools/ArdupilotMegaPlanner/Antenna/ITrackerOutput.cs index bee2aa98dffcc3a961cf32942ec1d1cdb5fdb83f..4791cae5f9a6fbc7e196e7c703bc2016606f6b9d 100644 --- a/Tools/ArdupilotMegaPlanner/Antenna/ITrackerOutput.cs +++ b/Tools/ArdupilotMegaPlanner/Antenna/ITrackerOutput.cs @@ -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; } diff --git a/Tools/ArdupilotMegaPlanner/Antenna/Maestro.cs b/Tools/ArdupilotMegaPlanner/Antenna/Maestro.cs index f77df0945010fd4f6689f7d79d525e3067eb1222..e7e52d3047fb31e8a8a64c2280174ed862974b0a 100644 --- a/Tools/ArdupilotMegaPlanner/Antenna/Maestro.cs +++ b/Tools/ArdupilotMegaPlanner/Antenna/Maestro.cs @@ -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> diff --git a/Tools/ArdupilotMegaPlanner/Antenna/Tracker.Designer.cs b/Tools/ArdupilotMegaPlanner/Antenna/Tracker.Designer.cs index 7ac7ab2cdc95416054cc471a900b535d57727ed9..90eea7c067138c18139a250c6c32c21c2f7184f7 100644 --- a/Tools/ArdupilotMegaPlanner/Antenna/Tracker.Designer.cs +++ b/Tools/ArdupilotMegaPlanner/Antenna/Tracker.Designer.cs @@ -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; diff --git a/Tools/ArdupilotMegaPlanner/Antenna/Tracker.cs b/Tools/ArdupilotMegaPlanner/Antenna/Tracker.cs index 589f67111d03ae31e9b530065797d48f0e820397..d768645b786f05e0f20bb330437045a3bb036eb0 100644 --- a/Tools/ArdupilotMegaPlanner/Antenna/Tracker.cs +++ b/Tools/ArdupilotMegaPlanner/Antenna/Tracker.cs @@ -7,6 +7,7 @@ using System.Linq; using System.Text; using System.Windows.Forms; using ArdupilotMega.Controls.BackstageView; +using ArdupilotMega.Comms; namespace ArdupilotMega.Antenna { diff --git a/Tools/ArdupilotMegaPlanner/Antenna/Tracker.resx b/Tools/ArdupilotMegaPlanner/Antenna/Tracker.resx index ee9137adcd31599c48ca5dd2490ba9eceed8fa4c..74e13663a7444cdee5b1374cd43e127b1e15a81c 100644 --- a/Tools/ArdupilotMegaPlanner/Antenna/Tracker.resx +++ b/Tools/ArdupilotMegaPlanner/Antenna/Tracker.resx @@ -750,7 +750,7 @@ <value>BUT_connect</value> </data> <data name=">>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=">>BUT_connect.Parent" xml:space="preserve"> <value>$this</value> diff --git a/Tools/ArdupilotMegaPlanner/ArduinoComms.cs b/Tools/ArdupilotMegaPlanner/Arduino/ArduinoComms.cs similarity index 94% rename from Tools/ArdupilotMegaPlanner/ArduinoComms.cs rename to Tools/ArdupilotMegaPlanner/Arduino/ArduinoComms.cs index a685523550ad40551ff98b5f33a91862ce4d06ba..9647491a7470e50ad21a7464f7925562ae352f2f 100644 --- a/Tools/ArdupilotMegaPlanner/ArduinoComms.cs +++ b/Tools/ArdupilotMegaPlanner/Arduino/ArduinoComms.cs @@ -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; } + } +} diff --git a/Tools/ArdupilotMegaPlanner/ArduinoDetect.cs b/Tools/ArdupilotMegaPlanner/Arduino/ArduinoDetect.cs similarity index 96% rename from Tools/ArdupilotMegaPlanner/ArduinoDetect.cs rename to Tools/ArdupilotMegaPlanner/Arduino/ArduinoDetect.cs index ffa350cb5d18f5259ec2b03a00ba0c64564fc544..19c8bdea71180c9b64ed59af7d15f21b3d59c3de 100644 --- a/Tools/ArdupilotMegaPlanner/ArduinoDetect.cs +++ b/Tools/ArdupilotMegaPlanner/Arduino/ArduinoDetect.cs @@ -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; + } + } } \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/ArduinoSTK.cs b/Tools/ArdupilotMegaPlanner/Arduino/ArduinoSTK.cs similarity index 96% rename from Tools/ArdupilotMegaPlanner/ArduinoSTK.cs rename to Tools/ArdupilotMegaPlanner/Arduino/ArduinoSTK.cs index 372cf568c8eaad0ad86fd4fd0dc56e1cb694ba00..3a3a825e66156523c07c62f6ddacd5fd692799e3 100644 --- a/Tools/ArdupilotMegaPlanner/ArduinoSTK.cs +++ b/Tools/ArdupilotMegaPlanner/Arduino/ArduinoSTK.cs @@ -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; + } + } } \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/ArduinoSTKv2.cs b/Tools/ArdupilotMegaPlanner/Arduino/ArduinoSTKv2.cs similarity index 96% rename from Tools/ArdupilotMegaPlanner/ArduinoSTKv2.cs rename to Tools/ArdupilotMegaPlanner/Arduino/ArduinoSTKv2.cs index 746a6f0e103f81e128e0431fe662d46404a0afc9..81351906f44bb2d151747cf79b9bf46593a5847e 100644 --- a/Tools/ArdupilotMegaPlanner/ArduinoSTKv2.cs +++ b/Tools/ArdupilotMegaPlanner/Arduino/ArduinoSTKv2.cs @@ -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; + } + } +} diff --git a/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj b/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj index 13dc37325c6f3877c012478d41955e1d2d460ea1..2e41a7222c06729e27203d4ea63edab94f2ddbbd 100644 --- a/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj +++ b/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj @@ -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" /> diff --git a/Tools/ArdupilotMegaPlanner/Camera.Designer.cs b/Tools/ArdupilotMegaPlanner/Camera.Designer.cs index a748b9749f0a47668426c308d2ff8bc4ca9ce8b5..b2ff93843e487e2472c14ac30a22819454ff1427 100644 --- a/Tools/ArdupilotMegaPlanner/Camera.Designer.cs +++ b/Tools/ArdupilotMegaPlanner/Camera.Designer.cs @@ -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; } } \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/Camera.resx b/Tools/ArdupilotMegaPlanner/Camera.resx index b5668d74bf212dd5c022072a99da02d83e7d2979..8e934149dfa7ff79517b06522558d77b2a2364ff 100644 --- a/Tools/ArdupilotMegaPlanner/Camera.resx +++ b/Tools/ArdupilotMegaPlanner/Camera.resx @@ -915,7 +915,7 @@ <value>BUT_save</value> </data> <data name=">>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=">>BUT_save.Parent" xml:space="preserve"> <value>$this</value> diff --git a/Tools/ArdupilotMegaPlanner/Common.cs b/Tools/ArdupilotMegaPlanner/Common.cs index c6453757d3a135e72063e82231276f97aaee14e0..30b539568839bc621d7edd7e255ef64635fa3c3b 100644 --- a/Tools/ArdupilotMegaPlanner/Common.cs +++ b/Tools/ArdupilotMegaPlanner/Common.cs @@ -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; diff --git a/Tools/ArdupilotMegaPlanner/CommsSerialInterface.cs b/Tools/ArdupilotMegaPlanner/Comms/CommsSerialInterface.cs similarity index 95% rename from Tools/ArdupilotMegaPlanner/CommsSerialInterface.cs rename to Tools/ArdupilotMegaPlanner/Comms/CommsSerialInterface.cs index cd85b924457228867f92a3f90fa697d83d9384cf..aee48f0402821aa301496975c617f6299b85c5b2 100644 --- a/Tools/ArdupilotMegaPlanner/CommsSerialInterface.cs +++ b/Tools/ArdupilotMegaPlanner/Comms/CommsSerialInterface.cs @@ -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; } + } +} diff --git a/Tools/ArdupilotMegaPlanner/CommsSerialPort.cs b/Tools/ArdupilotMegaPlanner/Comms/CommsSerialPort.cs similarity index 96% rename from Tools/ArdupilotMegaPlanner/CommsSerialPort.cs rename to Tools/ArdupilotMegaPlanner/Comms/CommsSerialPort.cs index 2fe153f2898fefaed848b2008eaa3035423c6c6a..ac07fc4a328dcd9b973198c61fbd526a312531fe 100644 --- a/Tools/ArdupilotMegaPlanner/CommsSerialPort.cs +++ b/Tools/ArdupilotMegaPlanner/Comms/CommsSerialPort.cs @@ -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; + } + } +} diff --git a/Tools/ArdupilotMegaPlanner/CommsTCPSerial.cs b/Tools/ArdupilotMegaPlanner/Comms/CommsTCPSerial.cs similarity index 94% rename from Tools/ArdupilotMegaPlanner/CommsTCPSerial.cs rename to Tools/ArdupilotMegaPlanner/Comms/CommsTCPSerial.cs index 76492e1e8b151af77132bc48d8bc97792f58b9f7..435e3f46ed36f97ebee3eaf26ff104b861a6463e 100644 --- a/Tools/ArdupilotMegaPlanner/CommsTCPSerial.cs +++ b/Tools/ArdupilotMegaPlanner/Comms/CommsTCPSerial.cs @@ -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"); } diff --git a/Tools/ArdupilotMegaPlanner/CommsUdpSerial.cs b/Tools/ArdupilotMegaPlanner/Comms/CommsUdpSerial.cs similarity index 95% rename from Tools/ArdupilotMegaPlanner/CommsUdpSerial.cs rename to Tools/ArdupilotMegaPlanner/Comms/CommsUdpSerial.cs index f5b5feb3e2b5392d2959aa6e47b497e1ab62e805..d569cad89fec10eab94f11b41ac08b64f754188b 100644 --- a/Tools/ArdupilotMegaPlanner/CommsUdpSerial.cs +++ b/Tools/ArdupilotMegaPlanner/Comms/CommsUdpSerial.cs @@ -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(); + } + } +} diff --git a/Tools/ArdupilotMegaPlanner/Controls/ConfigPanel.cs b/Tools/ArdupilotMegaPlanner/Controls/ConfigPanel.cs index 6e33d77c35c8ab15b3660b3c57785808e82f40ab..26ab3db6c24fa8f55341096fc205fa7354995b15 100644 --- a/Tools/ArdupilotMegaPlanner/Controls/ConfigPanel.cs +++ b/Tools/ArdupilotMegaPlanner/Controls/ConfigPanel.cs @@ -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); diff --git a/Tools/ArdupilotMegaPlanner/Controls/CustomMessageBox.cs b/Tools/ArdupilotMegaPlanner/Controls/CustomMessageBox.cs index e26038bdcf65b62420249dd25d5e4fbe8b545485..2326987b33ee649317a988714bcb527a2161a014 100644 --- a/Tools/ArdupilotMegaPlanner/Controls/CustomMessageBox.cs +++ b/Tools/ArdupilotMegaPlanner/Controls/CustomMessageBox.cs @@ -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", diff --git a/Tools/ArdupilotMegaPlanner/HUD.cs b/Tools/ArdupilotMegaPlanner/Controls/HUD.cs similarity index 97% rename from Tools/ArdupilotMegaPlanner/HUD.cs rename to Tools/ArdupilotMegaPlanner/Controls/HUD.cs index e87062fb4657561d65fb584f4ea526a9090b1c72..1ca4337e68696e180d43a61bbee8e802bb463d69 100644 --- a/Tools/ArdupilotMegaPlanner/HUD.cs +++ b/Tools/ArdupilotMegaPlanner/Controls/HUD.cs @@ -1,1606 +1,1606 @@ -using System; -using System.Collections.Generic; -using System.ComponentModel; -using System.Drawing; -using System.Data; -using System.Text; -using System.Windows.Forms; -using System.IO; -using System.Drawing.Imaging; - -using System.Threading; - -using System.Drawing.Drawing2D; -using log4net; -using OpenTK; -using OpenTK.Graphics.OpenGL; -using OpenTK.Graphics; - - -// Control written by Michael Oborne 2011 -// dual opengl and GDI+ - -namespace hud -{ - public class HUD : GLControl - { - private static readonly ILog log = LogManager.GetLogger( - System.Reflection.MethodBase.GetCurrentMethod().DeclaringType); - object paintlock = new object(); - object streamlock = new object(); - MemoryStream _streamjpg = new MemoryStream(); - [System.ComponentModel.Browsable(false)] - public MemoryStream streamjpg { get { lock (streamlock) { return _streamjpg; } } set { lock (streamlock) { _streamjpg = value; } } } - /// <summary> - /// this is to reduce cpu usage - /// </summary> - public bool streamjpgenable = false; - - Bitmap[] charbitmaps = new Bitmap[6000]; - int[] charbitmaptexid = new int[6000]; - int[] charwidth = new int[6000]; - - public int huddrawtime = 0; - - public bool opengl { get { return base.UseOpenGL; } set { base.UseOpenGL = value; } } - - bool started = false; - - public bool SixteenXNine = false; - - public HUD() - { - if (this.DesignMode) - { - opengl = false; - //return; - } - - //InitializeComponent(); - - graphicsObject = this; - graphicsObjectGDIP = Graphics.FromImage(objBitmap); - } - /* - private void InitializeComponent() - { - System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(HUD)); - this.SuspendLayout(); - // - // HUD - // - this.BackColor = System.Drawing.Color.Black; - this.Name = "HUD"; - resources.ApplyResources(this, "$this"); - this.ResumeLayout(false); - - }*/ - - float _roll = 0; - float _navroll = 0; - float _pitch = 0; - float _navpitch = 0; - float _heading = 0; - float _targetheading = 0; - float _alt = 0; - float _targetalt = 0; - float _groundspeed = 0; - float _airspeed = 0; - float _targetspeed = 0; - float _batterylevel = 0; - float _batteryremaining = 0; - float _gpsfix = 0; - float _gpshdop = 0; - float _disttowp = 0; - float _groundcourse = 0; - float _xtrack_error = 0; - float _turnrate = 0; - float _verticalspeed = 0; - float _linkqualitygcs = 0; - DateTime _datetime; - string _mode = "Manual"; - int _wpno = 0; - - [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")] - public float roll { get { return _roll; } set { if (_roll != value) { _roll = value; this.Invalidate(); } } } - [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")] - public float navroll { get { return _navroll; } set { if (_navroll != value) { _navroll = value; this.Invalidate(); } } } - [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")] - public float pitch { get { return _pitch; } set { if (_pitch != value) { _pitch = value; this.Invalidate(); } } } - [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")] - public float navpitch { get { return _navpitch; } set { if (_navpitch != value) { _navpitch = value; this.Invalidate(); } } } - [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")] - public float heading { get { return _heading; } set { if (_heading != value) { _heading = value; this.Invalidate(); } } } - [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")] - public float targetheading { get { return _targetheading; } set { if (_targetheading != value) { _targetheading = value; this.Invalidate(); } } } - [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")] - public float alt { get { return _alt; } set { if (_alt != value) { _alt = value; this.Invalidate(); } } } - [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")] - public float targetalt { get { return _targetalt; } set { if (_targetalt != value) { _targetalt = value; this.Invalidate(); } } } - [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")] - public float groundspeed { get { return _groundspeed; } set { if (_groundspeed != value) { _groundspeed = value; this.Invalidate(); } } } - [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")] - public float airspeed { get { return _airspeed; } set { if (_airspeed != value) { _airspeed = value; this.Invalidate(); } } } - [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")] - public float targetspeed { get { return _targetspeed; } set { if (_targetspeed != value) { _targetspeed = value; this.Invalidate(); } } } - [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")] - public float batterylevel { get { return _batterylevel; } set { if (_batterylevel != value) { _batterylevel = value; this.Invalidate(); } } } - [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")] - public float batteryremaining { get { return _batteryremaining; } set { if (_batteryremaining != value) { _batteryremaining = value; this.Invalidate(); } } } - [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")] - public float gpsfix { get { return _gpsfix; } set { if (_gpsfix != value) { _gpsfix = value; this.Invalidate(); } } } - [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")] - public float gpshdop { get { return _gpshdop; } set { if (_gpshdop != value) { _gpshdop = value; this.Invalidate(); } } } - [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")] - public float disttowp { get { return _disttowp; } set { if (_disttowp != value) { _disttowp = value; this.Invalidate(); } } } - [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")] - public string mode { get { return _mode; } set { if (_mode != value) { _mode = value; this.Invalidate(); } } } - [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")] - public int wpno { get { return _wpno; } set { if (_wpno != value) { _wpno = value; this.Invalidate(); } } } - [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")] - public float groundcourse { get { return _groundcourse; } set { if (_groundcourse != value) { _groundcourse = value; this.Invalidate(); } } } - [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")] - public float xtrack_error { get { return _xtrack_error; } set { if (_xtrack_error != value) { _xtrack_error = value; this.Invalidate(); } } } - [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")] - public float turnrate { get { return _turnrate; } set { if (_turnrate != value) { _turnrate = value; this.Invalidate(); } } } - [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")] - public float verticalspeed { get { return _verticalspeed; } set { if (_verticalspeed != value) { _verticalspeed = value; this.Invalidate(); } } } - [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")] - public float linkqualitygcs { get { return _linkqualitygcs; } set { if (_linkqualitygcs != value) { _linkqualitygcs = value; this.Invalidate(); } } } - [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")] - public DateTime datetime { get { return _datetime; } set { if (_datetime != value) { _datetime = value; this.Invalidate(); } } } - - [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")] - public int status { get; set; } - - int statuslast = 0; - DateTime armedtimer = DateTime.MinValue; - - public bool bgon = true; - public bool hudon = true; - - [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")] - public Color hudcolor { get { return whitePen.Color; } set { whitePen = new Pen(value, 2); } } - - Pen whitePen = new Pen(Color.White, 2); - - public Image bgimage { set { _bgimage = value; this.Invalidate(); } } - Image _bgimage; - - // move these global as they rarely change - reduce GC - Font font = new Font("Arial", 10); - Bitmap objBitmap = new Bitmap(1024, 1024); - int count = 0; - DateTime countdate = DateTime.Now; - HUD graphicsObject; - Graphics graphicsObjectGDIP; - - DateTime starttime = DateTime.MinValue; - - System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(HUD)); - - public override void Refresh() - { - //base.Refresh(); - OnPaint(new PaintEventArgs(this.CreateGraphics(),this.ClientRectangle)); - } - - protected override void OnLoad(EventArgs e) - { - if (opengl) - { - try - { - - GraphicsMode test = this.GraphicsMode; - log.Info(test.ToString()); - log.Info("Vendor: " + GL.GetString(StringName.Vendor)); - log.Info("Version: " + GL.GetString(StringName.Version)); - log.Info("Device: " + GL.GetString(StringName.Renderer)); - //Console.WriteLine("Extensions: " + GL.GetString(StringName.Extensions)); - - int[] viewPort = new int[4]; - - GL.GetInteger(GetPName.Viewport, viewPort); - - GL.MatrixMode(MatrixMode.Projection); - GL.LoadIdentity(); - GL.Ortho(0, Width, Height, 0, -1, 1); - GL.MatrixMode(MatrixMode.Modelview); - GL.LoadIdentity(); - - GL.PushAttrib(AttribMask.DepthBufferBit); - GL.Disable(EnableCap.DepthTest); - //GL.Enable(EnableCap.Texture2D); - GL.BlendFunc(BlendingFactorSrc.SrcAlpha, BlendingFactorDest.OneMinusSrcAlpha); - GL.Enable(EnableCap.Blend); - - } - catch (Exception ex) { log.Info("HUD opengl onload " + ex.ToString()); } - - try - { - GL.Hint(HintTarget.PerspectiveCorrectionHint, HintMode.Nicest); - - GL.Hint(HintTarget.LineSmoothHint, HintMode.Nicest); - GL.Hint(HintTarget.PolygonSmoothHint, HintMode.Nicest); - GL.Hint(HintTarget.PointSmoothHint, HintMode.Nicest); - - GL.Hint(HintTarget.TextureCompressionHint, HintMode.Nicest); - } - catch { } - - try - { - - GL.Enable(EnableCap.LineSmooth); - GL.Enable(EnableCap.PointSmooth); - GL.Enable(EnableCap.PolygonSmooth); - - } - catch { } - } - - started = true; - } - - bool inOnPaint = false; - string otherthread = ""; - - protected override void OnPaint(PaintEventArgs e) - { - //GL.Enable(EnableCap.AlphaTest) - - if (!started) - return; - - if (this.DesignMode) - { - e.Graphics.Clear(this.BackColor); - e.Graphics.Flush(); - } - - if ((DateTime.Now - starttime).TotalMilliseconds < 30 && (_bgimage == null)) - { - //Console.WriteLine("ms "+(DateTime.Now - starttime).TotalMilliseconds); - //e.Graphics.DrawImageUnscaled(objBitmap, 0, 0); - return; - } - - if (inOnPaint) - { - log.Info("Was in onpaint Hud th:" + System.Threading.Thread.CurrentThread.Name + " in " + otherthread); - return; - } - - otherthread = System.Threading.Thread.CurrentThread.Name; - - inOnPaint = true; - - starttime = DateTime.Now; - - try - { - - if (opengl) - { - MakeCurrent(); - - GL.Clear(ClearBufferMask.ColorBufferBit); - - } - - doPaint(e); - - if (opengl) - { - this.SwapBuffers(); - } - - } - catch (Exception ex) { log.Info(ex.ToString()); } - - inOnPaint = false; - - count++; - - huddrawtime += (int)(DateTime.Now - starttime).TotalMilliseconds; - - if (DateTime.Now.Second != countdate.Second) - { - countdate = DateTime.Now; - // Console.WriteLine("HUD " + count + " hz drawtime " + (huddrawtime / count) + " gl " + opengl); - if ((huddrawtime / count) > 1000) - opengl = false; - - count = 0; - huddrawtime = 0; - } - } - - void Clear(Color color) - { - if (opengl) - { - GL.ClearColor(color); - } else - { - graphicsObjectGDIP.Clear(color); - } - } - - const float rad2deg = (float)(180 / Math.PI); - const float deg2rad = (float)(1.0 / rad2deg); - - public void DrawArc(Pen penn,RectangleF rect, float start,float degrees) - { - if (opengl) - { - GL.LineWidth(penn.Width); - GL.Color4(penn.Color); - - GL.Begin(BeginMode.LineStrip); - start -= 90; - float x = 0, y = 0; - for (int i = (int)start; i <= start + degrees; i++) - { - x = (float)Math.Sin(i * deg2rad) * rect.Width / 2; - y = (float)Math.Cos(i * deg2rad) * rect.Height / 2; - x = x + rect.X + rect.Width / 2; - y = y + rect.Y + rect.Height / 2; - GL.Vertex2(x, y); - } - GL.End(); - } - else - { - graphicsObjectGDIP.DrawArc(penn, rect, start, degrees); - } - } - - public void DrawEllipse(Pen penn, Rectangle rect) - { - if (opengl) - { - GL.LineWidth(penn.Width); - GL.Color4(penn.Color); - - GL.Begin(BeginMode.LineLoop); - float x, y; - for (float i = 0; i < 360; i += 1) - { - x = (float)Math.Sin(i * deg2rad) * rect.Width / 2; - y = (float)Math.Cos(i * deg2rad) * rect.Height / 2; - x = x + rect.X + rect.Width / 2; - y = y + rect.Y + rect.Height / 2; - GL.Vertex2(x, y); - } - GL.End(); - } - else - { - graphicsObjectGDIP.DrawEllipse(penn, rect); - } - } - - int texture; - Bitmap bitmap = new Bitmap(512,512); - - public void DrawImage(Image img, int x, int y, int width, int height) - { - if (opengl) - { - if (img == null) - return; - //bitmap = new Bitmap(512,512); - - using (Graphics graphics = Graphics.FromImage(bitmap)) - { - graphics.CompositingQuality = System.Drawing.Drawing2D.CompositingQuality.HighSpeed; - graphics.InterpolationMode = System.Drawing.Drawing2D.InterpolationMode.NearestNeighbor; - graphics.SmoothingMode = System.Drawing.Drawing2D.SmoothingMode.HighSpeed; - //draw the image into the target bitmap - graphics.DrawImage(img, 0, 0, bitmap.Width, bitmap.Height); - } - - - GL.DeleteTexture(texture); - - GL.GenTextures(1, out texture); - GL.BindTexture(TextureTarget.Texture2D, texture); - - BitmapData data = bitmap.LockBits(new System.Drawing.Rectangle(0, 0, bitmap.Width, bitmap.Height), - ImageLockMode.ReadOnly, System.Drawing.Imaging.PixelFormat.Format32bppArgb); - - //Console.WriteLine("w {0} h {1}",data.Width, data.Height); - - GL.TexImage2D(TextureTarget.Texture2D, 0, PixelInternalFormat.Rgba, data.Width, data.Height, 0, - OpenTK.Graphics.OpenGL.PixelFormat.Bgra, PixelType.UnsignedByte, data.Scan0); - - bitmap.UnlockBits(data); - - GL.TexParameter(TextureTarget.Texture2D, TextureParameterName.TextureMinFilter, (int)TextureMinFilter.Linear); - GL.TexParameter(TextureTarget.Texture2D, TextureParameterName.TextureMagFilter, (int)TextureMagFilter.Linear); - - GL.Enable(EnableCap.Texture2D); - - GL.BindTexture(TextureTarget.Texture2D, texture); - - GL.Begin(BeginMode.Quads); - - GL.TexCoord2(0.0f, 1.0f); GL.Vertex2(0, this.Height); - GL.TexCoord2(1.0f, 1.0f); GL.Vertex2(this.Width, this.Height); - GL.TexCoord2(1.0f, 0.0f); GL.Vertex2(this.Width, 0); - GL.TexCoord2(0.0f, 0.0f); GL.Vertex2(0, 0); - - GL.End(); - - GL.Disable(EnableCap.Texture2D); - } - else - { - graphicsObjectGDIP.DrawImage(img,x,y,width,height); - } - } - - public void DrawPath(Pen penn, GraphicsPath gp) - { - try - { - DrawPolygon(penn, gp.PathPoints); - } - catch { } - } - - public void FillPath(Brush brushh, GraphicsPath gp) - { - try - { - FillPolygon(brushh, gp.PathPoints); - } - catch { } - } - - public void SetClip(Rectangle rect) - { - - } - - public void ResetClip() - { - - } - - public void ResetTransform() - { - if (opengl) - { - GL.LoadIdentity(); - } - else - { - graphicsObjectGDIP.ResetTransform(); - } - } - - public void RotateTransform(float angle) - { - if (opengl) - { - GL.Rotate(angle, 0, 0, 1); - } - else - { - graphicsObjectGDIP.RotateTransform(angle); - } - } - - public void TranslateTransform(float x, float y) - { - if (opengl) - { - GL.Translate(x, y, 0f); - } - else - { - graphicsObjectGDIP.TranslateTransform(x, y); - } - } - - public void FillPolygon(Brush brushh, Point[] list) - { - if (opengl) - { - GL.Begin(BeginMode.TriangleFan); - GL.Color4(((SolidBrush)brushh).Color); - foreach (Point pnt in list) - { - GL.Vertex2(pnt.X, pnt.Y); - } - GL.Vertex2(list[list.Length - 1].X, list[list.Length - 1].Y); - GL.End(); - } - else - { - graphicsObjectGDIP.FillPolygon(brushh, list); - } - } - - public void FillPolygon(Brush brushh, PointF[] list) - { - if (opengl) - { - GL.Begin(BeginMode.Quads); - GL.Color4(((SolidBrush)brushh).Color); - foreach (PointF pnt in list) - { - GL.Vertex2(pnt.X, pnt.Y); - } - GL.Vertex2(list[0].X, list[0].Y); - GL.End(); - } - else - { - graphicsObjectGDIP.FillPolygon(brushh, list); - } - } - - public void DrawPolygon(Pen penn, Point[] list) - { - if (opengl) - { - GL.LineWidth(penn.Width); - GL.Color4(penn.Color); - - GL.Begin(BeginMode.LineLoop); - foreach (Point pnt in list) - { - GL.Vertex2(pnt.X, pnt.Y); - } - GL.End(); - } - else - { - graphicsObjectGDIP.DrawPolygon(penn, list); - } - } - - public void DrawPolygon(Pen penn, PointF[] list) - { - if (opengl) - { - GL.LineWidth(penn.Width); - GL.Color4(penn.Color); - - GL.Begin(BeginMode.LineLoop); - foreach (PointF pnt in list) - { - GL.Vertex2(pnt.X, pnt.Y); - } - - GL.End(); - } - else - { - graphicsObjectGDIP.DrawPolygon(penn, list); - } - } - - - public void FillRectangle(Brush brushh, RectangleF rectf) - { - if (opengl) - { - float x1 = rectf.X; - float y1 = rectf.Y; - - float width = rectf.Width; - float height = rectf.Height; - - GL.Begin(BeginMode.Quads); - - if (((Type)brushh.GetType()) == typeof(LinearGradientBrush)) - { - LinearGradientBrush temp = (LinearGradientBrush)brushh; - GL.Color4(temp.LinearColors[0]); - } - else - { - GL.Color4(((SolidBrush)brushh).Color.R / 255f, ((SolidBrush)brushh).Color.G / 255f, ((SolidBrush)brushh).Color.B / 255f, ((SolidBrush)brushh).Color.A / 255f); - } - - GL.Vertex2(x1, y1); - GL.Vertex2(x1 + width, y1); - - if (((Type)brushh.GetType()) == typeof(LinearGradientBrush)) - { - LinearGradientBrush temp = (LinearGradientBrush)brushh; - GL.Color4(temp.LinearColors[1]); - } - else - { - GL.Color4(((SolidBrush)brushh).Color.R / 255f, ((SolidBrush)brushh).Color.G / 255f, ((SolidBrush)brushh).Color.B / 255f, ((SolidBrush)brushh).Color.A / 255f); - } - - GL.Vertex2(x1 + width, y1 + height); - GL.Vertex2(x1, y1 + height); - GL.End(); - } - else - { - graphicsObjectGDIP.FillRectangle(brushh, rectf); - } - } - - public void DrawRectangle(Pen penn, RectangleF rect) - { - DrawRectangle(penn, rect.X, rect.Y, rect.Width, rect.Height); - } - - public void DrawRectangle(Pen penn, double x1, double y1, double width, double height) - { - - if (opengl) - { - GL.LineWidth(penn.Width); - GL.Color4(penn.Color); - - GL.Begin(BeginMode.LineLoop); - GL.Vertex2(x1, y1); - GL.Vertex2(x1 + width, y1); - GL.Vertex2(x1 + width, y1 + height); - GL.Vertex2(x1, y1 + height); - GL.End(); - } - else - { - graphicsObjectGDIP.DrawRectangle(penn, (float)x1, (float)y1, (float)width, (float)height); - } - } - - public void DrawLine(Pen penn, double x1, double y1, double x2, double y2) - { - - if (opengl) - { - GL.Color4(penn.Color); - GL.LineWidth(penn.Width); - - GL.Begin(BeginMode.Lines); - GL.Vertex2(x1, y1); - GL.Vertex2(x2, y2); - GL.End(); - } - else - { - graphicsObjectGDIP.DrawLine(penn, (float)x1, (float)y1, (float)x2, (float)y2); - } - } - - void doPaint(PaintEventArgs e) - { - bool isNaN = false; - try - { - if (graphicsObjectGDIP == null || !opengl && (objBitmap.Width != this.Width || objBitmap.Height != this.Height)) - { - objBitmap = new Bitmap(this.Width, this.Height); - graphicsObjectGDIP = Graphics.FromImage(objBitmap); - - graphicsObjectGDIP.SmoothingMode = SmoothingMode.AntiAlias; - graphicsObjectGDIP.InterpolationMode = InterpolationMode.NearestNeighbor; - graphicsObjectGDIP.CompositingMode = CompositingMode.SourceOver; - graphicsObjectGDIP.CompositingQuality = CompositingQuality.HighSpeed; - graphicsObjectGDIP.PixelOffsetMode = PixelOffsetMode.HighSpeed; - graphicsObjectGDIP.TextRenderingHint = System.Drawing.Text.TextRenderingHint.SystemDefault; - } - - - graphicsObject.Clear(Color.Gray); - - if (_bgimage != null) - { - bgon = false; - graphicsObject.DrawImage(_bgimage, 0, 0, this.Width, this.Height); - - if (hudon == false) - { - return; - } - } - else - { - bgon = true; - } - - - if (float.IsNaN(_roll) || float.IsNaN(_pitch) || float.IsNaN(_heading)) - { - isNaN = true; - - _roll = 0; - _pitch = 0; - _heading = 0; - } - - graphicsObject.TranslateTransform(this.Width / 2, this.Height / 2); - - - - graphicsObject.RotateTransform(-_roll); - - - int fontsize = this.Height / 30; // = 10 - int fontoffset = fontsize - 10; - - float every5deg = -this.Height / 60; - - float pitchoffset = -_pitch * every5deg; - - int halfwidth = this.Width / 2; - int halfheight = this.Height / 2; - - SolidBrush whiteBrush = new SolidBrush(whitePen.Color); - - Pen blackPen = new Pen(Color.Black, 2); - Pen greenPen = new Pen(Color.Green, 2); - Pen redPen = new Pen(Color.Red, 2); - - // draw sky - if (bgon == true) - { - RectangleF bg = new RectangleF(-halfwidth * 2, -halfheight * 2, this.Width * 2, halfheight * 2 + pitchoffset); - - if (bg.Height != 0) - { - LinearGradientBrush linearBrush = new LinearGradientBrush(bg, Color.Blue, - Color.LightBlue, LinearGradientMode.Vertical); - - graphicsObject.FillRectangle(linearBrush, bg); - } - // draw ground - - bg = new RectangleF(-halfwidth * 2, pitchoffset, this.Width * 2, halfheight * 2 - pitchoffset); - - if (bg.Height != 0) - { - LinearGradientBrush linearBrush = new LinearGradientBrush(bg, Color.FromArgb(0x9b, 0xb8, 0x24), - Color.FromArgb(0x41, 0x4f, 0x07), LinearGradientMode.Vertical); - - graphicsObject.FillRectangle(linearBrush, bg); - } - - //draw centerline - graphicsObject.DrawLine(whitePen, -halfwidth * 2, pitchoffset + 0, halfwidth * 2, pitchoffset + 0); - } - - graphicsObject.ResetTransform(); - - graphicsObject.SetClip(new Rectangle(0, this.Height / 14, this.Width, this.Height - this.Height / 14)); - - graphicsObject.TranslateTransform(this.Width / 2, this.Height / 2); - graphicsObject.RotateTransform(-_roll); - - // draw armed - - if (status != statuslast) - { - armedtimer = DateTime.Now; - } - - if (status == 3) // not armed - { - //if ((armedtimer.AddSeconds(8) > DateTime.Now)) - { - drawstring(graphicsObject, "DISARMED", font, fontsize + 10, Brushes.Red, -85, halfheight / -3); - statuslast = status; - } - } - else if (status == 4) // armed - { - if ((armedtimer.AddSeconds(8) > DateTime.Now)) - { - drawstring(graphicsObject, "ARMED", font, fontsize + 20, Brushes.Red, -70, halfheight / -3); - statuslast = status; - } - } - - //draw pitch - - int lengthshort = this.Width / 12; - int lengthlong = this.Width / 8; - - for (int a = -90; a <= 90; a += 5) - { - // limit to 40 degrees - if (a >= _pitch - 34 && a <= _pitch + 25) - { - if (a % 10 == 0) - { - if (a == 0) - { - graphicsObject.DrawLine(greenPen, this.Width / 2 - lengthlong - halfwidth, pitchoffset + a * every5deg, this.Width / 2 + lengthlong - halfwidth, pitchoffset + a * every5deg); - } - else - { - graphicsObject.DrawLine(whitePen, this.Width / 2 - lengthlong - halfwidth, pitchoffset + a * every5deg, this.Width / 2 + lengthlong - halfwidth, pitchoffset + a * every5deg); - } - drawstring(graphicsObject, a.ToString(), font, fontsize + 2, whiteBrush, this.Width / 2 - lengthlong - 30 - halfwidth - (int)(fontoffset * 1.7), pitchoffset + a * every5deg - 8 - fontoffset); - } - else - { - graphicsObject.DrawLine(whitePen, this.Width / 2 - lengthshort - halfwidth, pitchoffset + a * every5deg, this.Width / 2 + lengthshort - halfwidth, pitchoffset + a * every5deg); - //drawstring(e,a.ToString(), new Font("Arial", 10), whiteBrush, this.Width / 2 - lengthshort - 20 - halfwidth, this.Height / 2 + pitchoffset + a * every5deg - 8); - } - } - } - - graphicsObject.ResetTransform(); - - // draw roll ind needle - - graphicsObject.TranslateTransform(this.Width / 2, this.Height / 2 + this.Height / 14); - - graphicsObject.RotateTransform(-_roll); - - Point[] pointlist = new Point[3]; - - lengthlong = this.Height / 66; - - int extra = this.Height / 15 * 7; - - pointlist[0] = new Point(0, -lengthlong * 2 - extra); - pointlist[1] = new Point(-lengthlong, -lengthlong - extra); - pointlist[2] = new Point(lengthlong, -lengthlong - extra); - - if (Math.Abs(_roll) > 45) - { - redPen.Width = 10; - } - - graphicsObject.DrawPolygon(redPen, pointlist); - - redPen.Width = 2; - - for (int a = -45; a <= 45; a += 15) - { - graphicsObject.ResetTransform(); - graphicsObject.TranslateTransform(this.Width / 2, this.Height / 2 + this.Height / 14); - graphicsObject.RotateTransform(a); - drawstring(graphicsObject, Math.Abs(a).ToString("##"), font, fontsize, whiteBrush, 0 - 6 - fontoffset, -lengthlong * 2 - extra); - graphicsObject.DrawLine(whitePen, 0, -halfheight, 0, -halfheight - 10); - } - - graphicsObject.ResetTransform(); - - //draw centre / current att - - Rectangle centercircle = new Rectangle(halfwidth - 10, halfheight - 10, 20, 20); - - graphicsObject.DrawEllipse(redPen, centercircle); - graphicsObject.DrawLine(redPen, centercircle.Left - 10, halfheight, centercircle.Left, halfheight); - graphicsObject.DrawLine(redPen, centercircle.Right, halfheight, centercircle.Right + 10, halfheight); - graphicsObject.DrawLine(redPen, centercircle.Left + centercircle.Width / 2, centercircle.Top, centercircle.Left + centercircle.Width / 2, centercircle.Top - 10); - - // draw roll ind - - Rectangle arcrect = new Rectangle(this.Width / 2 - this.Height / 2, this.Height / 14, this.Height, this.Height); - - graphicsObject.DrawArc(whitePen, arcrect, 180 + 45, 90); - - //draw heading ind - - graphicsObject.ResetClip(); - - Rectangle headbg = new Rectangle(0, 0, this.Width - 0, this.Height / 14); - - graphicsObject.DrawRectangle(blackPen, headbg); - - SolidBrush solidBrush = new SolidBrush(Color.FromArgb(0x55, 0xff, 0xff, 0xff)); - - graphicsObject.FillRectangle(solidBrush, headbg); - - // center - graphicsObject.DrawLine(redPen, headbg.Width / 2, headbg.Bottom, headbg.Width / 2, headbg.Top); - - //bottom line - graphicsObject.DrawLine(whitePen, headbg.Left + 5, headbg.Bottom - 5, headbg.Width - 5, headbg.Bottom - 5); - - float space = (headbg.Width - 10) / 60.0f; - int start = (int)Math.Round((_heading - 30),1); - - // draw for outside the 60 deg - if (_targetheading < start) - { - greenPen.Width = 6; - graphicsObject.DrawLine(greenPen, headbg.Left + 5 + space * 0, headbg.Bottom, headbg.Left + 5 + space * (0), headbg.Top); - } - if (_targetheading > _heading + 30) - { - greenPen.Width = 6; - graphicsObject.DrawLine(greenPen, headbg.Left + 5 + space * 60, headbg.Bottom, headbg.Left + 5 + space * (60), headbg.Top); - } - - for (int a = start; a <= _heading + 30; a += 1) - { - // target heading - if (((int)(a + 360) % 360) == (int)_targetheading) - { - greenPen.Width = 6; - graphicsObject.DrawLine(greenPen, headbg.Left + 5 + space * (a - start), headbg.Bottom, headbg.Left + 5 + space * (a - start), headbg.Top); - } - - if (((int)(a + 360) % 360) == (int)_groundcourse) - { - blackPen.Width = 6; - graphicsObject.DrawLine(blackPen, headbg.Left + 5 + space * (a - start), headbg.Bottom, headbg.Left + 5 + space * (a - start), headbg.Top); - blackPen.Width = 2; - } - - if ((int)a % 5 == 0) - { - //Console.WriteLine(a + " " + Math.Round(a, 1, MidpointRounding.AwayFromZero)); - //Console.WriteLine(space +" " + a +" "+ (headbg.Left + 5 + space * (a - start))); - graphicsObject.DrawLine(whitePen, headbg.Left + 5 + space * (a - start), headbg.Bottom - 5, headbg.Left + 5 + space * (a - start), headbg.Bottom - 10); - int disp = (int)a; - if (disp < 0) - disp += 360; - disp = disp % 360; - if (disp == 0) - { - drawstring(graphicsObject, "N".PadLeft(2), font, fontsize + 4, whiteBrush, headbg.Left - 5 + space * (a - start) - fontoffset, headbg.Bottom - 24 - (int)(fontoffset * 1.7)); - } - else if (disp == 90) - { - drawstring(graphicsObject, "E".PadLeft(2), font, fontsize + 4, whiteBrush, headbg.Left - 5 + space * (a - start) - fontoffset, headbg.Bottom - 24 - (int)(fontoffset * 1.7)); - } - else if (disp == 180) - { - drawstring(graphicsObject, "S".PadLeft(2), font, fontsize + 4, whiteBrush, headbg.Left - 5 + space * (a - start) - fontoffset, headbg.Bottom - 24 - (int)(fontoffset * 1.7)); - } - else if (disp == 270) - { - drawstring(graphicsObject, "W".PadLeft(2), font, fontsize + 4, whiteBrush, headbg.Left - 5 + space * (a - start) - fontoffset, headbg.Bottom - 24 - (int)(fontoffset * 1.7)); - } - else - { - drawstring(graphicsObject, (disp % 360).ToString().PadLeft(3), font, fontsize, whiteBrush, headbg.Left - 5 + space * (a - start) - fontoffset, headbg.Bottom - 24 - (int)(fontoffset * 1.7)); - } - } - } - - // Console.WriteLine("HUD 0 " + (DateTime.Now - starttime).TotalMilliseconds + " " + DateTime.Now.Millisecond); - - // xtrack error - // center - - float xtspace = this.Width / 10.0f / 3.0f; - int pad = 10; - - float myxtrack_error = _xtrack_error; - - myxtrack_error = Math.Min(myxtrack_error, 40); - myxtrack_error = Math.Max(myxtrack_error, -40); - - // xtrack - distance scale - space - float loc = myxtrack_error / 20.0f * xtspace; - - // current xtrack - if (Math.Abs(myxtrack_error) == 40) - { - greenPen.Color = Color.FromArgb(128, greenPen.Color); - } - - graphicsObject.DrawLine(greenPen, this.Width / 10 + loc, headbg.Bottom + 5, this.Width / 10 + loc, headbg.Bottom + this.Height / 10); - - greenPen.Color = Color.FromArgb(255, greenPen.Color); - - graphicsObject.DrawLine(whitePen, this.Width / 10, headbg.Bottom + 5, this.Width / 10, headbg.Bottom + this.Height / 10); - - graphicsObject.DrawLine(whitePen, this.Width / 10 - xtspace, headbg.Bottom + 5 + pad, this.Width / 10 - xtspace, headbg.Bottom + this.Height / 10 - pad); - - graphicsObject.DrawLine(whitePen, this.Width / 10 - xtspace * 2, headbg.Bottom + 5 + pad, this.Width / 10 - xtspace * 2, headbg.Bottom + this.Height / 10 - pad); - - graphicsObject.DrawLine(whitePen, this.Width / 10 + xtspace, headbg.Bottom + 5 + pad, this.Width / 10 + xtspace, headbg.Bottom + this.Height / 10 - pad); - - graphicsObject.DrawLine(whitePen, this.Width / 10 + xtspace * 2, headbg.Bottom + 5 + pad, this.Width / 10 + xtspace * 2, headbg.Bottom + this.Height / 10 - pad); - - // rate of turn - - whitePen.Width = 4; - graphicsObject.DrawLine(whitePen, this.Width / 10 - xtspace * 2 - xtspace / 2, headbg.Bottom + this.Height / 10 + 10, this.Width / 10 - xtspace * 2 - xtspace / 2 + xtspace, headbg.Bottom + this.Height / 10 + 10); - - graphicsObject.DrawLine(whitePen, this.Width / 10 - xtspace * 0 - xtspace / 2, headbg.Bottom + this.Height / 10 + 10, this.Width / 10 - xtspace * 0 - xtspace / 2 + xtspace, headbg.Bottom + this.Height / 10 + 10); - - graphicsObject.DrawLine(whitePen, this.Width / 10 + xtspace * 2 - xtspace / 2, headbg.Bottom + this.Height / 10 + 10, this.Width / 10 + xtspace * 2 - xtspace / 2 + xtspace, headbg.Bottom + this.Height / 10 + 10); - - float myturnrate = _turnrate; - float trwidth = (this.Width / 10 + xtspace * 2 - xtspace / 2) - (this.Width / 10 - xtspace * 2 - xtspace / 2); - - float range = 12; - - myturnrate = Math.Min(myturnrate, range / 2); - myturnrate = Math.Max(myturnrate, (range / 2) * -1.0f); - - loc = myturnrate / range * trwidth; - - greenPen.Width = 4; - - if (Math.Abs(myturnrate) == (range / 2)) - { - greenPen.Color = Color.FromArgb(128, greenPen.Color); - } - - graphicsObject.DrawLine(greenPen, this.Width / 10 + loc - xtspace / 2, headbg.Bottom + this.Height / 10 + 10 + 3, this.Width / 10 + loc + xtspace / 2, headbg.Bottom + this.Height / 10 + 10 + 3); - graphicsObject.DrawLine(greenPen, this.Width / 10 + loc, headbg.Bottom + this.Height / 10 + 10 + 3, this.Width / 10 + loc, headbg.Bottom + this.Height / 10 + 10 + 10); - - greenPen.Color = Color.FromArgb(255, greenPen.Color); - - whitePen.Width = 2; - - - - // left scroller - - Rectangle scrollbg = new Rectangle(0, halfheight - halfheight / 2, this.Width / 10, this.Height / 2); - - graphicsObject.DrawRectangle(whitePen, scrollbg); - - graphicsObject.FillRectangle(solidBrush, scrollbg); - - Point[] arrow = new Point[5]; - - arrow[0] = new Point(0, -10); - arrow[1] = new Point(scrollbg.Width - 10, -10); - arrow[2] = new Point(scrollbg.Width - 5, 0); - arrow[3] = new Point(scrollbg.Width - 10, 10); - arrow[4] = new Point(0, 10); - - graphicsObject.TranslateTransform(0, this.Height / 2); - - int viewrange = 26; - - float speed = _airspeed; - if (speed == 0) - speed = _groundspeed; - - space = (scrollbg.Height) / (float)viewrange; - start = ((int)speed - viewrange / 2); - - if (start > _targetspeed) - { - greenPen.Color = Color.FromArgb(128, greenPen.Color); - greenPen.Width = 6; - graphicsObject.DrawLine(greenPen, scrollbg.Left, scrollbg.Top, scrollbg.Left + scrollbg.Width, scrollbg.Top); - greenPen.Color = Color.FromArgb(255, greenPen.Color); - } - if ((speed + viewrange / 2) < _targetspeed) - { - greenPen.Color = Color.FromArgb(128, greenPen.Color); - greenPen.Width = 6; - graphicsObject.DrawLine(greenPen, scrollbg.Left, scrollbg.Top - space * viewrange, scrollbg.Left + scrollbg.Width, scrollbg.Top - space * viewrange); - greenPen.Color = Color.FromArgb(255, greenPen.Color); - } - - for (int a = (int)start; a <= (speed + viewrange / 2); a += 1) - { - if (a == (int)_targetspeed && _targetspeed != 0) - { - greenPen.Width = 6; - graphicsObject.DrawLine(greenPen, scrollbg.Left, scrollbg.Top - space * (a - start), scrollbg.Left + scrollbg.Width, scrollbg.Top - space * (a - start)); - } - if (a % 5 == 0) - { - //Console.WriteLine(a + " " + scrollbg.Right + " " + (scrollbg.Top - space * (a - start)) + " " + (scrollbg.Right - 20) + " " + (scrollbg.Top - space * (a - start))); - graphicsObject.DrawLine(whitePen, scrollbg.Right, scrollbg.Top - space * (a - start), scrollbg.Right - 10, scrollbg.Top - space * (a - start)); - drawstring(graphicsObject, a.ToString().PadLeft(5), font, fontsize, whiteBrush, scrollbg.Right - 50 - 4 * fontoffset, scrollbg.Top - space * (a - start) - 6 - fontoffset); - } - } - - graphicsObject.DrawPolygon(blackPen, arrow); - graphicsObject.FillPolygon(Brushes.Black, arrow); - drawstring(graphicsObject, ((int)speed).ToString("0"), font, 10, Brushes.AliceBlue, 0, -9); - - graphicsObject.ResetTransform(); - - // extra text data - - drawstring(graphicsObject, "AS " + _airspeed.ToString("0.0"), font, fontsize, whiteBrush, 1, scrollbg.Bottom + 5); - drawstring(graphicsObject, "GS " + _groundspeed.ToString("0.0"), font, fontsize, whiteBrush, 1, scrollbg.Bottom + fontsize + 2 + 10); - - //drawstring(e,, new Font("Arial", fontsize + 2), whiteBrush, 1, scrollbg.Bottom + fontsize + 2 + 10); - - // right scroller - - scrollbg = new Rectangle(this.Width - this.Width / 10, halfheight - halfheight / 2, this.Width / 10, this.Height / 2); - - graphicsObject.DrawRectangle(whitePen, scrollbg); - - graphicsObject.FillRectangle(solidBrush, scrollbg); - - arrow = new Point[5]; - - arrow[0] = new Point(0, -10); - arrow[1] = new Point(scrollbg.Width - 10, -10); - arrow[2] = new Point(scrollbg.Width - 5, 0); - arrow[3] = new Point(scrollbg.Width - 10, 10); - arrow[4] = new Point(0, 10); - - - - graphicsObject.TranslateTransform(0, this.Height / 2); - - - - - viewrange = 26; - - space = (scrollbg.Height) / (float)viewrange; - start = ((int)_alt - viewrange / 2); - - if (start > _targetalt) - { - greenPen.Color = Color.FromArgb(128, greenPen.Color); - greenPen.Width = 6; - graphicsObject.DrawLine(greenPen, scrollbg.Left, scrollbg.Top, scrollbg.Left + scrollbg.Width, scrollbg.Top); - greenPen.Color = Color.FromArgb(255, greenPen.Color); - } - if ((_alt + viewrange / 2) < _targetalt) - { - greenPen.Color = Color.FromArgb(128, greenPen.Color); - greenPen.Width = 6; - graphicsObject.DrawLine(greenPen, scrollbg.Left, scrollbg.Top - space * viewrange, scrollbg.Left + scrollbg.Width, scrollbg.Top - space * viewrange); - greenPen.Color = Color.FromArgb(255, greenPen.Color); - } - - for (int a = (int)start; a <= (_alt + viewrange / 2); a += 1) - { - if (a == Math.Round(_targetalt) && _targetalt != 0) - { - greenPen.Width = 6; - graphicsObject.DrawLine(greenPen, scrollbg.Left, scrollbg.Top - space * (a - start), scrollbg.Left + scrollbg.Width, scrollbg.Top - space * (a - start)); - } - if (a % 5 == 0) - { - //Console.WriteLine(a + " " + scrollbg.Left + " " + (scrollbg.Top - space * (a - start)) + " " + (scrollbg.Left + 20) + " " + (scrollbg.Top - space * (a - start))); - graphicsObject.DrawLine(whitePen, scrollbg.Left, scrollbg.Top - space * (a - start), scrollbg.Left + 10, scrollbg.Top - space * (a - start)); - drawstring(graphicsObject, a.ToString().PadLeft(5), font, fontsize, whiteBrush, scrollbg.Left + 7 + (int)(0 * fontoffset), scrollbg.Top - space * (a - start) - 6 - fontoffset); - } - } - - greenPen.Width = 4; - - // vsi - - graphicsObject.ResetTransform(); - - PointF[] poly = new PointF[4]; - - poly[0] = new PointF(scrollbg.Left, scrollbg.Top); - poly[1] = new PointF(scrollbg.Left - scrollbg.Width / 4, scrollbg.Top + scrollbg.Width / 4); - poly[2] = new PointF(scrollbg.Left - scrollbg.Width / 4, scrollbg.Bottom - scrollbg.Width / 4); - poly[3] = new PointF(scrollbg.Left, scrollbg.Bottom); - - //verticalspeed - - viewrange = 12; - - _verticalspeed = Math.Min(viewrange / 2, _verticalspeed); - _verticalspeed = Math.Max(viewrange / -2, _verticalspeed); - - float scaledvalue = _verticalspeed / -viewrange * (scrollbg.Bottom - scrollbg.Top); - - float linespace = (float)1 / -viewrange * (scrollbg.Bottom - scrollbg.Top); - - PointF[] polyn = new PointF[4]; - - polyn[0] = new PointF(scrollbg.Left, scrollbg.Top + (scrollbg.Bottom - scrollbg.Top) / 2); - polyn[1] = new PointF(scrollbg.Left - scrollbg.Width / 4, scrollbg.Top + (scrollbg.Bottom - scrollbg.Top) / 2); - polyn[2] = polyn[1]; - float peak = 0; - if (scaledvalue > 0) - { - peak = -scrollbg.Width / 4; - if (scrollbg.Top + (scrollbg.Bottom - scrollbg.Top) / 2 + scaledvalue + peak < scrollbg.Top + (scrollbg.Bottom - scrollbg.Top) / 2) - peak = -scaledvalue; - } - else if (scaledvalue < 0) - { - peak = +scrollbg.Width / 4; - if (scrollbg.Top + (scrollbg.Bottom - scrollbg.Top) / 2 + scaledvalue + peak > scrollbg.Top + (scrollbg.Bottom - scrollbg.Top) / 2) - peak = -scaledvalue; - } - - polyn[2] = new PointF(scrollbg.Left - scrollbg.Width / 4, scrollbg.Top + (scrollbg.Bottom - scrollbg.Top) / 2 + scaledvalue + peak); - polyn[3] = new PointF(scrollbg.Left, scrollbg.Top + (scrollbg.Bottom - scrollbg.Top) / 2 + scaledvalue); - - //graphicsObject.DrawPolygon(redPen, poly); - graphicsObject.FillPolygon(Brushes.Blue, polyn); - - // draw outsidebox - graphicsObject.DrawPolygon(whitePen, poly); - - for (int a = 1; a < viewrange; a++) - { - graphicsObject.DrawLine(whitePen, scrollbg.Left - scrollbg.Width / 4, scrollbg.Top - linespace * a, scrollbg.Left - scrollbg.Width / 8, scrollbg.Top - linespace * a); - } - - // draw arrow and text - - graphicsObject.ResetTransform(); - graphicsObject.TranslateTransform(this.Width, this.Height / 2); - graphicsObject.RotateTransform(180); - - graphicsObject.DrawPolygon(blackPen, arrow); - graphicsObject.FillPolygon(Brushes.Black, arrow); - graphicsObject.ResetTransform(); - graphicsObject.TranslateTransform(0, this.Height / 2); - - drawstring(graphicsObject, ((int)_alt).ToString("0"), font, 10, Brushes.AliceBlue, scrollbg.Left + 10, -9); - graphicsObject.ResetTransform(); - - // mode and wp dist and wp - - drawstring(graphicsObject, _mode, font, fontsize, whiteBrush, scrollbg.Left - 30, scrollbg.Bottom + 5); - drawstring(graphicsObject, (int)_disttowp + ">" + _wpno, font, fontsize, whiteBrush, scrollbg.Left - 30, scrollbg.Bottom + fontsize + 2 + 10); - - graphicsObject.DrawLine(greenPen, scrollbg.Left - 5, scrollbg.Top - (int)(fontsize * 2.2) - 2 - 20, scrollbg.Left - 5, scrollbg.Top - (int)(fontsize) - 2 - 20); - graphicsObject.DrawLine(greenPen, scrollbg.Left - 10, scrollbg.Top - (int)(fontsize * 2.2) - 2 - 15, scrollbg.Left - 10, scrollbg.Top - (int)(fontsize) - 2 - 20); - graphicsObject.DrawLine(greenPen, scrollbg.Left - 15, scrollbg.Top - (int)(fontsize * 2.2) - 2 - 10, scrollbg.Left - 15, scrollbg.Top - (int)(fontsize ) - 2 - 20); - - drawstring(graphicsObject, _linkqualitygcs.ToString("0") + "%", font, fontsize, whiteBrush, scrollbg.Left, scrollbg.Top - (int)(fontsize * 2.2) - 2 - 20); - if (_linkqualitygcs == 0) - { - graphicsObject.DrawLine(redPen, scrollbg.Left, scrollbg.Top - (int)(fontsize * 2.2) - 2 - 20, scrollbg.Left + 50, scrollbg.Top - (int)(fontsize * 2.2) - 2); - - graphicsObject.DrawLine(redPen, scrollbg.Left, scrollbg.Top - (int)(fontsize * 2.2) - 2, scrollbg.Left + 50, scrollbg.Top - (int)(fontsize * 2.2) - 2 - 20); - } - drawstring(graphicsObject, _datetime.ToString("HH:mm:ss"), font, fontsize, whiteBrush, scrollbg.Left - 20, scrollbg.Top - fontsize - 2 - 20); - - - // battery - - graphicsObject.ResetTransform(); - - drawstring(graphicsObject, "Bat", font, fontsize + 2, whiteBrush, fontsize, this.Height - 30 - fontoffset); - drawstring(graphicsObject, _batterylevel.ToString("0.00v"), font, fontsize + 2, whiteBrush, fontsize * 4, this.Height - 30 - fontoffset); - drawstring(graphicsObject, _batteryremaining.ToString("0%"), font, fontsize + 2, whiteBrush, fontsize * 9, this.Height - 30 - fontoffset); - - // gps - - string gps = ""; - - if (_gpsfix == 0) - { - gps = ("GPS: No GPS"); - } - else if (_gpsfix == 1) - { - gps = ("GPS: No Fix"); - } - else if (_gpsfix == 2) - { - gps = ("GPS: 3D Fix"); - } - else if (_gpsfix == 3) - { - gps = ("GPS: 3D Fix"); - } - - drawstring(graphicsObject, gps, font, fontsize + 2, whiteBrush, this.Width - 10 * fontsize, this.Height - 30 - fontoffset); - - - if (isNaN) - drawstring(graphicsObject, "NaN Error " + DateTime.Now, font, this.Height / 30 + 10, Brushes.Red, 50, 50); - - - if (!opengl) - { - e.Graphics.DrawImageUnscaled(objBitmap, 0, 0); - } - - if (DesignMode) - { - return; - } - - // Console.WriteLine("HUD 1 " + (DateTime.Now - starttime).TotalMilliseconds + " " + DateTime.Now.Millisecond); - - ImageCodecInfo ici = GetImageCodec("image/jpeg"); - EncoderParameters eps = new EncoderParameters(1); - eps.Param[0] = new EncoderParameter(System.Drawing.Imaging.Encoder.Quality, 50L); // or whatever other quality value you want - - lock (streamlock) - { - if (streamjpgenable || streamjpg == null) // init image and only update when needed - { - if (opengl) - { - objBitmap = GrabScreenshot(); - } - streamjpg = new MemoryStream(); - objBitmap.Save(streamjpg, ici, eps); - //objBitmap.Save(streamjpg,ImageFormat.Bmp); - } - } - } - catch (Exception ex) - { - log.Info("hud error "+ex.ToString()); - } - } - - protected override void OnPaintBackground(PaintEventArgs e) - { - //base.OnPaintBackground(e); - } - - ImageCodecInfo GetImageCodec(string mimetype) - { - foreach (ImageCodecInfo ici in ImageCodecInfo.GetImageEncoders()) - { - if (ici.MimeType == mimetype) return ici; - } - return null; - } - - // Returns a System.Drawing.Bitmap with the contents of the current framebuffer - public new Bitmap GrabScreenshot() - { - if (GraphicsContext.CurrentContext == null) - throw new GraphicsContextMissingException(); - - Bitmap bmp = new Bitmap(this.ClientSize.Width, this.ClientSize.Height); - System.Drawing.Imaging.BitmapData data = - bmp.LockBits(this.ClientRectangle, System.Drawing.Imaging.ImageLockMode.WriteOnly, System.Drawing.Imaging.PixelFormat.Format24bppRgb); - GL.ReadPixels(0, 0, this.ClientSize.Width, this.ClientSize.Height,OpenTK.Graphics.OpenGL.PixelFormat.Bgr, PixelType.UnsignedByte, data.Scan0); - bmp.UnlockBits(data); - - bmp.RotateFlip(RotateFlipType.RotateNoneFlipY); - return bmp; - } - - - float wrap360(float noin) - { - if (noin < 0) - return noin + 360; - return noin; - } - - /// <summary> - /// pen for drawstring - /// </summary> - Pen P = new Pen(Color.FromArgb(0x26, 0x27, 0x28), 2f); - /// <summary> - /// pth for drawstring - /// </summary> - GraphicsPath pth = new GraphicsPath(); - - void drawstring(HUD e, string text, Font font, float fontsize, Brush brush, float x, float y) - { - if (!opengl) - { - drawstring(graphicsObjectGDIP, text, font, fontsize, brush, x, y); - return; - } - - if (text == null || text == "") - return; - /* - OpenTK.Graphics.Begin(); - GL.PushMatrix(); - GL.Translate(x, y, 0); - printer.Print(text, font, c); - GL.PopMatrix(); printer.End(); - */ - - char[] chars = text.ToCharArray(); - - float maxy = 1; - - foreach (char cha in chars) - { - int charno = (int)cha; - - int charid = charno + (128 * (int)fontsize); // 128 * 40 * 5;128 - - if (charbitmaps[charid] == null) - { - charbitmaps[charid] = new Bitmap(128, 128, System.Drawing.Imaging.PixelFormat.Format32bppArgb); - - charbitmaps[charid].MakeTransparent(Color.Transparent); - - //charbitmaptexid - - float maxx = this.Width / 150; // for space - - - // create bitmap - using (Graphics gfx = Graphics.FromImage(charbitmaps[charid])) - { - pth.Reset(); - - if (text != null) - pth.AddString(cha + "", font.FontFamily, 0, fontsize + 5, new Point((int)0, (int)0), StringFormat.GenericTypographic); - - gfx.SmoothingMode = System.Drawing.Drawing2D.SmoothingMode.AntiAlias; - - gfx.DrawPath(P, pth); - - //Draw the face - - gfx.FillPath(brush, pth); - - - if (pth.PointCount > 0) - { - foreach (PointF pnt in pth.PathPoints) - { - if (pnt.X > maxx) - maxx = pnt.X; - - if (pnt.Y > maxy) - maxy = pnt.Y; - } - } - } - - charwidth[charid] = (int)(maxx + 2); - - //charbitmaps[charid] = charbitmaps[charid].Clone(new RectangleF(0, 0, maxx + 2, maxy + 2), charbitmaps[charid].PixelFormat); - - //charbitmaps[charno * (int)fontsize].Save(charno + " " + (int)fontsize + ".png"); - - // create texture - int textureId; - GL.TexEnv(TextureEnvTarget.TextureEnv, TextureEnvParameter.TextureEnvMode, (float)TextureEnvModeCombine.Replace);//Important, or wrong color on some computers - - Bitmap bitmap = charbitmaps[charid]; - GL.GenTextures(1, out textureId); - GL.BindTexture(TextureTarget.Texture2D, textureId); - - BitmapData data = bitmap.LockBits(new System.Drawing.Rectangle(0, 0, bitmap.Width, bitmap.Height), ImageLockMode.ReadOnly, System.Drawing.Imaging.PixelFormat.Format32bppArgb); - - GL.TexImage2D(TextureTarget.Texture2D, 0, PixelInternalFormat.Rgba, data.Width, data.Height, 0, OpenTK.Graphics.OpenGL.PixelFormat.Bgra, PixelType.UnsignedByte, data.Scan0); - - GL.TexParameter(TextureTarget.Texture2D, TextureParameterName.TextureMinFilter, (int)TextureMinFilter.Linear); - GL.TexParameter(TextureTarget.Texture2D, TextureParameterName.TextureMagFilter, (int)TextureMagFilter.Linear); - - // GL.TexParameter(TextureTarget.Texture2D, TextureParameterName.TextureMagFilter, (int)All.Nearest); - //GL.TexParameter(TextureTarget.Texture2D, TextureParameterName.TextureMinFilter, (int)All.Nearest); - GL.Finish(); - bitmap.UnlockBits(data); - - charbitmaptexid[charid] = textureId; - } - - //GL.Enable(EnableCap.Blend); - GL.BlendFunc(BlendingFactorSrc.SrcAlpha, BlendingFactorDest.OneMinusSrcAlpha); - - GL.Enable(EnableCap.Texture2D); - GL.BindTexture(TextureTarget.Texture2D, charbitmaptexid[charid]); - - float scale = 1.0f; - - GL.Begin(BeginMode.Quads); - GL.TexCoord2(0, 0); GL.Vertex2(x, y); - GL.TexCoord2(1, 0); GL.Vertex2(x + charbitmaps[charid].Width * scale, y); - GL.TexCoord2(1, 1); GL.Vertex2(x + charbitmaps[charid].Width * scale, y + charbitmaps[charid].Height * scale); - GL.TexCoord2(0, 1); GL.Vertex2(x + 0, y + charbitmaps[charid].Height * scale); - GL.End(); - - //GL.Disable(EnableCap.Blend); - GL.Disable(EnableCap.Texture2D); - - x += charwidth[charid] * scale; - } - } - - void drawstring(Graphics e, string text, Font font, float fontsize, Brush brush, float x, float y) - { - if (text == null || text == "") - return; - - pth.Reset(); - - if (text != null) - pth.AddString(text, font.FontFamily, 0, fontsize + 5, new Point((int)x, (int)y), StringFormat.GenericTypographic); - - //Draw the edge - // this uses lots of cpu time - - //e.SmoothingMode = SmoothingMode.HighSpeed; - - if (e == null || P == null || pth == null || pth.PointCount == 0) - return; - - //if (!ArdupilotMega.MainV2.MONO) - e.DrawPath(P, pth); - - //Draw the face - - e.FillPath(brush, pth); - - //pth.Dispose(); - } - - protected override void OnHandleCreated(EventArgs e) - { - try - { - if (opengl) - { - base.OnHandleCreated(e); - } - } - catch (Exception ex) { log.Info(ex.ToString()); opengl = false; } // macs fail here - } - - protected override void OnHandleDestroyed(EventArgs e) - { - try - { - if (opengl) - { - base.OnHandleDestroyed(e); - } - } - catch (Exception ex) { log.Info(ex.ToString()); opengl = false; } - } - - protected override void OnResize(EventArgs e) - { - if (DesignMode || !started) - return; - - - if (SixteenXNine) - { - this.Height = (int)(this.Width / 1.777f); - } - else - { - // 4x3 - this.Height = (int)(this.Width / 1.333f); - } - - base.OnResize(e); - - graphicsObjectGDIP = Graphics.FromImage(objBitmap); - - charbitmaps = new Bitmap[charbitmaps.Length]; - - try - { - if (opengl) - { - foreach (int texid in charbitmaptexid) - { - if (texid != 0) - GL.DeleteTexture(texid); - } - } - } - catch { } - - GC.Collect(); - - try - { - if (opengl) - { - GL.MatrixMode(MatrixMode.Projection); - GL.LoadIdentity(); - GL.Ortho(0, Width, Height, 0, -1, 1); - GL.MatrixMode(MatrixMode.Modelview); - GL.LoadIdentity(); - - GL.Viewport(0, 0, Width, Height); - } - } - catch { } - - } - } +using System; +using System.Collections.Generic; +using System.ComponentModel; +using System.Drawing; +using System.Data; +using System.Text; +using System.Windows.Forms; +using System.IO; +using System.Drawing.Imaging; + +using System.Threading; + +using System.Drawing.Drawing2D; +using log4net; +using OpenTK; +using OpenTK.Graphics.OpenGL; +using OpenTK.Graphics; + + +// Control written by Michael Oborne 2011 +// dual opengl and GDI+ + +namespace ArdupilotMega.Controls +{ + public class HUD : GLControl + { + private static readonly ILog log = LogManager.GetLogger( + System.Reflection.MethodBase.GetCurrentMethod().DeclaringType); + object paintlock = new object(); + object streamlock = new object(); + MemoryStream _streamjpg = new MemoryStream(); + [System.ComponentModel.Browsable(false)] + public MemoryStream streamjpg { get { lock (streamlock) { return _streamjpg; } } set { lock (streamlock) { _streamjpg = value; } } } + /// <summary> + /// this is to reduce cpu usage + /// </summary> + public bool streamjpgenable = false; + + Bitmap[] charbitmaps = new Bitmap[6000]; + int[] charbitmaptexid = new int[6000]; + int[] charwidth = new int[6000]; + + public int huddrawtime = 0; + + public bool opengl { get { return base.UseOpenGL; } set { base.UseOpenGL = value; } } + + bool started = false; + + public bool SixteenXNine = false; + + public HUD() + { + if (this.DesignMode) + { + opengl = false; + //return; + } + + //InitializeComponent(); + + graphicsObject = this; + graphicsObjectGDIP = Graphics.FromImage(objBitmap); + } + /* + private void InitializeComponent() + { + System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(HUD)); + this.SuspendLayout(); + // + // HUD + // + this.BackColor = System.Drawing.Color.Black; + this.Name = "HUD"; + resources.ApplyResources(this, "$this"); + this.ResumeLayout(false); + + }*/ + + float _roll = 0; + float _navroll = 0; + float _pitch = 0; + float _navpitch = 0; + float _heading = 0; + float _targetheading = 0; + float _alt = 0; + float _targetalt = 0; + float _groundspeed = 0; + float _airspeed = 0; + float _targetspeed = 0; + float _batterylevel = 0; + float _batteryremaining = 0; + float _gpsfix = 0; + float _gpshdop = 0; + float _disttowp = 0; + float _groundcourse = 0; + float _xtrack_error = 0; + float _turnrate = 0; + float _verticalspeed = 0; + float _linkqualitygcs = 0; + DateTime _datetime; + string _mode = "Manual"; + int _wpno = 0; + + [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")] + public float roll { get { return _roll; } set { if (_roll != value) { _roll = value; this.Invalidate(); } } } + [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")] + public float navroll { get { return _navroll; } set { if (_navroll != value) { _navroll = value; this.Invalidate(); } } } + [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")] + public float pitch { get { return _pitch; } set { if (_pitch != value) { _pitch = value; this.Invalidate(); } } } + [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")] + public float navpitch { get { return _navpitch; } set { if (_navpitch != value) { _navpitch = value; this.Invalidate(); } } } + [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")] + public float heading { get { return _heading; } set { if (_heading != value) { _heading = value; this.Invalidate(); } } } + [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")] + public float targetheading { get { return _targetheading; } set { if (_targetheading != value) { _targetheading = value; this.Invalidate(); } } } + [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")] + public float alt { get { return _alt; } set { if (_alt != value) { _alt = value; this.Invalidate(); } } } + [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")] + public float targetalt { get { return _targetalt; } set { if (_targetalt != value) { _targetalt = value; this.Invalidate(); } } } + [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")] + public float groundspeed { get { return _groundspeed; } set { if (_groundspeed != value) { _groundspeed = value; this.Invalidate(); } } } + [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")] + public float airspeed { get { return _airspeed; } set { if (_airspeed != value) { _airspeed = value; this.Invalidate(); } } } + [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")] + public float targetspeed { get { return _targetspeed; } set { if (_targetspeed != value) { _targetspeed = value; this.Invalidate(); } } } + [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")] + public float batterylevel { get { return _batterylevel; } set { if (_batterylevel != value) { _batterylevel = value; this.Invalidate(); } } } + [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")] + public float batteryremaining { get { return _batteryremaining; } set { if (_batteryremaining != value) { _batteryremaining = value; this.Invalidate(); } } } + [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")] + public float gpsfix { get { return _gpsfix; } set { if (_gpsfix != value) { _gpsfix = value; this.Invalidate(); } } } + [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")] + public float gpshdop { get { return _gpshdop; } set { if (_gpshdop != value) { _gpshdop = value; this.Invalidate(); } } } + [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")] + public float disttowp { get { return _disttowp; } set { if (_disttowp != value) { _disttowp = value; this.Invalidate(); } } } + [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")] + public string mode { get { return _mode; } set { if (_mode != value) { _mode = value; this.Invalidate(); } } } + [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")] + public int wpno { get { return _wpno; } set { if (_wpno != value) { _wpno = value; this.Invalidate(); } } } + [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")] + public float groundcourse { get { return _groundcourse; } set { if (_groundcourse != value) { _groundcourse = value; this.Invalidate(); } } } + [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")] + public float xtrack_error { get { return _xtrack_error; } set { if (_xtrack_error != value) { _xtrack_error = value; this.Invalidate(); } } } + [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")] + public float turnrate { get { return _turnrate; } set { if (_turnrate != value) { _turnrate = value; this.Invalidate(); } } } + [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")] + public float verticalspeed { get { return _verticalspeed; } set { if (_verticalspeed != value) { _verticalspeed = value; this.Invalidate(); } } } + [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")] + public float linkqualitygcs { get { return _linkqualitygcs; } set { if (_linkqualitygcs != value) { _linkqualitygcs = value; this.Invalidate(); } } } + [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")] + public DateTime datetime { get { return _datetime; } set { if (_datetime != value) { _datetime = value; this.Invalidate(); } } } + + [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")] + public int status { get; set; } + + int statuslast = 0; + DateTime armedtimer = DateTime.MinValue; + + public bool bgon = true; + public bool hudon = true; + + [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")] + public Color hudcolor { get { return whitePen.Color; } set { whitePen = new Pen(value, 2); } } + + Pen whitePen = new Pen(Color.White, 2); + + public Image bgimage { set { _bgimage = value; this.Invalidate(); } } + Image _bgimage; + + // move these global as they rarely change - reduce GC + Font font = new Font("Arial", 10); + Bitmap objBitmap = new Bitmap(1024, 1024); + int count = 0; + DateTime countdate = DateTime.Now; + HUD graphicsObject; + Graphics graphicsObjectGDIP; + + DateTime starttime = DateTime.MinValue; + + System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(HUD)); + + public override void Refresh() + { + //base.Refresh(); + OnPaint(new PaintEventArgs(this.CreateGraphics(),this.ClientRectangle)); + } + + protected override void OnLoad(EventArgs e) + { + if (opengl) + { + try + { + + GraphicsMode test = this.GraphicsMode; + log.Info(test.ToString()); + log.Info("Vendor: " + GL.GetString(StringName.Vendor)); + log.Info("Version: " + GL.GetString(StringName.Version)); + log.Info("Device: " + GL.GetString(StringName.Renderer)); + //Console.WriteLine("Extensions: " + GL.GetString(StringName.Extensions)); + + int[] viewPort = new int[4]; + + GL.GetInteger(GetPName.Viewport, viewPort); + + GL.MatrixMode(MatrixMode.Projection); + GL.LoadIdentity(); + GL.Ortho(0, Width, Height, 0, -1, 1); + GL.MatrixMode(MatrixMode.Modelview); + GL.LoadIdentity(); + + GL.PushAttrib(AttribMask.DepthBufferBit); + GL.Disable(EnableCap.DepthTest); + //GL.Enable(EnableCap.Texture2D); + GL.BlendFunc(BlendingFactorSrc.SrcAlpha, BlendingFactorDest.OneMinusSrcAlpha); + GL.Enable(EnableCap.Blend); + + } + catch (Exception ex) { log.Info("HUD opengl onload " + ex.ToString()); } + + try + { + GL.Hint(HintTarget.PerspectiveCorrectionHint, HintMode.Nicest); + + GL.Hint(HintTarget.LineSmoothHint, HintMode.Nicest); + GL.Hint(HintTarget.PolygonSmoothHint, HintMode.Nicest); + GL.Hint(HintTarget.PointSmoothHint, HintMode.Nicest); + + GL.Hint(HintTarget.TextureCompressionHint, HintMode.Nicest); + } + catch { } + + try + { + + GL.Enable(EnableCap.LineSmooth); + GL.Enable(EnableCap.PointSmooth); + GL.Enable(EnableCap.PolygonSmooth); + + } + catch { } + } + + started = true; + } + + bool inOnPaint = false; + string otherthread = ""; + + protected override void OnPaint(PaintEventArgs e) + { + //GL.Enable(EnableCap.AlphaTest) + + if (!started) + return; + + if (this.DesignMode) + { + e.Graphics.Clear(this.BackColor); + e.Graphics.Flush(); + } + + if ((DateTime.Now - starttime).TotalMilliseconds < 30 && (_bgimage == null)) + { + //Console.WriteLine("ms "+(DateTime.Now - starttime).TotalMilliseconds); + //e.Graphics.DrawImageUnscaled(objBitmap, 0, 0); + return; + } + + if (inOnPaint) + { + log.Info("Was in onpaint Hud th:" + System.Threading.Thread.CurrentThread.Name + " in " + otherthread); + return; + } + + otherthread = System.Threading.Thread.CurrentThread.Name; + + inOnPaint = true; + + starttime = DateTime.Now; + + try + { + + if (opengl) + { + MakeCurrent(); + + GL.Clear(ClearBufferMask.ColorBufferBit); + + } + + doPaint(e); + + if (opengl) + { + this.SwapBuffers(); + } + + } + catch (Exception ex) { log.Info(ex.ToString()); } + + inOnPaint = false; + + count++; + + huddrawtime += (int)(DateTime.Now - starttime).TotalMilliseconds; + + if (DateTime.Now.Second != countdate.Second) + { + countdate = DateTime.Now; + // Console.WriteLine("HUD " + count + " hz drawtime " + (huddrawtime / count) + " gl " + opengl); + if ((huddrawtime / count) > 1000) + opengl = false; + + count = 0; + huddrawtime = 0; + } + } + + void Clear(Color color) + { + if (opengl) + { + GL.ClearColor(color); + } else + { + graphicsObjectGDIP.Clear(color); + } + } + + const float rad2deg = (float)(180 / Math.PI); + const float deg2rad = (float)(1.0 / rad2deg); + + public void DrawArc(Pen penn,RectangleF rect, float start,float degrees) + { + if (opengl) + { + GL.LineWidth(penn.Width); + GL.Color4(penn.Color); + + GL.Begin(BeginMode.LineStrip); + start -= 90; + float x = 0, y = 0; + for (int i = (int)start; i <= start + degrees; i++) + { + x = (float)Math.Sin(i * deg2rad) * rect.Width / 2; + y = (float)Math.Cos(i * deg2rad) * rect.Height / 2; + x = x + rect.X + rect.Width / 2; + y = y + rect.Y + rect.Height / 2; + GL.Vertex2(x, y); + } + GL.End(); + } + else + { + graphicsObjectGDIP.DrawArc(penn, rect, start, degrees); + } + } + + public void DrawEllipse(Pen penn, Rectangle rect) + { + if (opengl) + { + GL.LineWidth(penn.Width); + GL.Color4(penn.Color); + + GL.Begin(BeginMode.LineLoop); + float x, y; + for (float i = 0; i < 360; i += 1) + { + x = (float)Math.Sin(i * deg2rad) * rect.Width / 2; + y = (float)Math.Cos(i * deg2rad) * rect.Height / 2; + x = x + rect.X + rect.Width / 2; + y = y + rect.Y + rect.Height / 2; + GL.Vertex2(x, y); + } + GL.End(); + } + else + { + graphicsObjectGDIP.DrawEllipse(penn, rect); + } + } + + int texture; + Bitmap bitmap = new Bitmap(512,512); + + public void DrawImage(Image img, int x, int y, int width, int height) + { + if (opengl) + { + if (img == null) + return; + //bitmap = new Bitmap(512,512); + + using (Graphics graphics = Graphics.FromImage(bitmap)) + { + graphics.CompositingQuality = System.Drawing.Drawing2D.CompositingQuality.HighSpeed; + graphics.InterpolationMode = System.Drawing.Drawing2D.InterpolationMode.NearestNeighbor; + graphics.SmoothingMode = System.Drawing.Drawing2D.SmoothingMode.HighSpeed; + //draw the image into the target bitmap + graphics.DrawImage(img, 0, 0, bitmap.Width, bitmap.Height); + } + + + GL.DeleteTexture(texture); + + GL.GenTextures(1, out texture); + GL.BindTexture(TextureTarget.Texture2D, texture); + + BitmapData data = bitmap.LockBits(new System.Drawing.Rectangle(0, 0, bitmap.Width, bitmap.Height), + ImageLockMode.ReadOnly, System.Drawing.Imaging.PixelFormat.Format32bppArgb); + + //Console.WriteLine("w {0} h {1}",data.Width, data.Height); + + GL.TexImage2D(TextureTarget.Texture2D, 0, PixelInternalFormat.Rgba, data.Width, data.Height, 0, + OpenTK.Graphics.OpenGL.PixelFormat.Bgra, PixelType.UnsignedByte, data.Scan0); + + bitmap.UnlockBits(data); + + GL.TexParameter(TextureTarget.Texture2D, TextureParameterName.TextureMinFilter, (int)TextureMinFilter.Linear); + GL.TexParameter(TextureTarget.Texture2D, TextureParameterName.TextureMagFilter, (int)TextureMagFilter.Linear); + + GL.Enable(EnableCap.Texture2D); + + GL.BindTexture(TextureTarget.Texture2D, texture); + + GL.Begin(BeginMode.Quads); + + GL.TexCoord2(0.0f, 1.0f); GL.Vertex2(0, this.Height); + GL.TexCoord2(1.0f, 1.0f); GL.Vertex2(this.Width, this.Height); + GL.TexCoord2(1.0f, 0.0f); GL.Vertex2(this.Width, 0); + GL.TexCoord2(0.0f, 0.0f); GL.Vertex2(0, 0); + + GL.End(); + + GL.Disable(EnableCap.Texture2D); + } + else + { + graphicsObjectGDIP.DrawImage(img,x,y,width,height); + } + } + + public void DrawPath(Pen penn, GraphicsPath gp) + { + try + { + DrawPolygon(penn, gp.PathPoints); + } + catch { } + } + + public void FillPath(Brush brushh, GraphicsPath gp) + { + try + { + FillPolygon(brushh, gp.PathPoints); + } + catch { } + } + + public void SetClip(Rectangle rect) + { + + } + + public void ResetClip() + { + + } + + public void ResetTransform() + { + if (opengl) + { + GL.LoadIdentity(); + } + else + { + graphicsObjectGDIP.ResetTransform(); + } + } + + public void RotateTransform(float angle) + { + if (opengl) + { + GL.Rotate(angle, 0, 0, 1); + } + else + { + graphicsObjectGDIP.RotateTransform(angle); + } + } + + public void TranslateTransform(float x, float y) + { + if (opengl) + { + GL.Translate(x, y, 0f); + } + else + { + graphicsObjectGDIP.TranslateTransform(x, y); + } + } + + public void FillPolygon(Brush brushh, Point[] list) + { + if (opengl) + { + GL.Begin(BeginMode.TriangleFan); + GL.Color4(((SolidBrush)brushh).Color); + foreach (Point pnt in list) + { + GL.Vertex2(pnt.X, pnt.Y); + } + GL.Vertex2(list[list.Length - 1].X, list[list.Length - 1].Y); + GL.End(); + } + else + { + graphicsObjectGDIP.FillPolygon(brushh, list); + } + } + + public void FillPolygon(Brush brushh, PointF[] list) + { + if (opengl) + { + GL.Begin(BeginMode.Quads); + GL.Color4(((SolidBrush)brushh).Color); + foreach (PointF pnt in list) + { + GL.Vertex2(pnt.X, pnt.Y); + } + GL.Vertex2(list[0].X, list[0].Y); + GL.End(); + } + else + { + graphicsObjectGDIP.FillPolygon(brushh, list); + } + } + + public void DrawPolygon(Pen penn, Point[] list) + { + if (opengl) + { + GL.LineWidth(penn.Width); + GL.Color4(penn.Color); + + GL.Begin(BeginMode.LineLoop); + foreach (Point pnt in list) + { + GL.Vertex2(pnt.X, pnt.Y); + } + GL.End(); + } + else + { + graphicsObjectGDIP.DrawPolygon(penn, list); + } + } + + public void DrawPolygon(Pen penn, PointF[] list) + { + if (opengl) + { + GL.LineWidth(penn.Width); + GL.Color4(penn.Color); + + GL.Begin(BeginMode.LineLoop); + foreach (PointF pnt in list) + { + GL.Vertex2(pnt.X, pnt.Y); + } + + GL.End(); + } + else + { + graphicsObjectGDIP.DrawPolygon(penn, list); + } + } + + + public void FillRectangle(Brush brushh, RectangleF rectf) + { + if (opengl) + { + float x1 = rectf.X; + float y1 = rectf.Y; + + float width = rectf.Width; + float height = rectf.Height; + + GL.Begin(BeginMode.Quads); + + if (((Type)brushh.GetType()) == typeof(LinearGradientBrush)) + { + LinearGradientBrush temp = (LinearGradientBrush)brushh; + GL.Color4(temp.LinearColors[0]); + } + else + { + GL.Color4(((SolidBrush)brushh).Color.R / 255f, ((SolidBrush)brushh).Color.G / 255f, ((SolidBrush)brushh).Color.B / 255f, ((SolidBrush)brushh).Color.A / 255f); + } + + GL.Vertex2(x1, y1); + GL.Vertex2(x1 + width, y1); + + if (((Type)brushh.GetType()) == typeof(LinearGradientBrush)) + { + LinearGradientBrush temp = (LinearGradientBrush)brushh; + GL.Color4(temp.LinearColors[1]); + } + else + { + GL.Color4(((SolidBrush)brushh).Color.R / 255f, ((SolidBrush)brushh).Color.G / 255f, ((SolidBrush)brushh).Color.B / 255f, ((SolidBrush)brushh).Color.A / 255f); + } + + GL.Vertex2(x1 + width, y1 + height); + GL.Vertex2(x1, y1 + height); + GL.End(); + } + else + { + graphicsObjectGDIP.FillRectangle(brushh, rectf); + } + } + + public void DrawRectangle(Pen penn, RectangleF rect) + { + DrawRectangle(penn, rect.X, rect.Y, rect.Width, rect.Height); + } + + public void DrawRectangle(Pen penn, double x1, double y1, double width, double height) + { + + if (opengl) + { + GL.LineWidth(penn.Width); + GL.Color4(penn.Color); + + GL.Begin(BeginMode.LineLoop); + GL.Vertex2(x1, y1); + GL.Vertex2(x1 + width, y1); + GL.Vertex2(x1 + width, y1 + height); + GL.Vertex2(x1, y1 + height); + GL.End(); + } + else + { + graphicsObjectGDIP.DrawRectangle(penn, (float)x1, (float)y1, (float)width, (float)height); + } + } + + public void DrawLine(Pen penn, double x1, double y1, double x2, double y2) + { + + if (opengl) + { + GL.Color4(penn.Color); + GL.LineWidth(penn.Width); + + GL.Begin(BeginMode.Lines); + GL.Vertex2(x1, y1); + GL.Vertex2(x2, y2); + GL.End(); + } + else + { + graphicsObjectGDIP.DrawLine(penn, (float)x1, (float)y1, (float)x2, (float)y2); + } + } + + void doPaint(PaintEventArgs e) + { + bool isNaN = false; + try + { + if (graphicsObjectGDIP == null || !opengl && (objBitmap.Width != this.Width || objBitmap.Height != this.Height)) + { + objBitmap = new Bitmap(this.Width, this.Height); + graphicsObjectGDIP = Graphics.FromImage(objBitmap); + + graphicsObjectGDIP.SmoothingMode = SmoothingMode.AntiAlias; + graphicsObjectGDIP.InterpolationMode = InterpolationMode.NearestNeighbor; + graphicsObjectGDIP.CompositingMode = CompositingMode.SourceOver; + graphicsObjectGDIP.CompositingQuality = CompositingQuality.HighSpeed; + graphicsObjectGDIP.PixelOffsetMode = PixelOffsetMode.HighSpeed; + graphicsObjectGDIP.TextRenderingHint = System.Drawing.Text.TextRenderingHint.SystemDefault; + } + + + graphicsObject.Clear(Color.Gray); + + if (_bgimage != null) + { + bgon = false; + graphicsObject.DrawImage(_bgimage, 0, 0, this.Width, this.Height); + + if (hudon == false) + { + return; + } + } + else + { + bgon = true; + } + + + if (float.IsNaN(_roll) || float.IsNaN(_pitch) || float.IsNaN(_heading)) + { + isNaN = true; + + _roll = 0; + _pitch = 0; + _heading = 0; + } + + graphicsObject.TranslateTransform(this.Width / 2, this.Height / 2); + + + + graphicsObject.RotateTransform(-_roll); + + + int fontsize = this.Height / 30; // = 10 + int fontoffset = fontsize - 10; + + float every5deg = -this.Height / 60; + + float pitchoffset = -_pitch * every5deg; + + int halfwidth = this.Width / 2; + int halfheight = this.Height / 2; + + SolidBrush whiteBrush = new SolidBrush(whitePen.Color); + + Pen blackPen = new Pen(Color.Black, 2); + Pen greenPen = new Pen(Color.Green, 2); + Pen redPen = new Pen(Color.Red, 2); + + // draw sky + if (bgon == true) + { + RectangleF bg = new RectangleF(-halfwidth * 2, -halfheight * 2, this.Width * 2, halfheight * 2 + pitchoffset); + + if (bg.Height != 0) + { + LinearGradientBrush linearBrush = new LinearGradientBrush(bg, Color.Blue, + Color.LightBlue, LinearGradientMode.Vertical); + + graphicsObject.FillRectangle(linearBrush, bg); + } + // draw ground + + bg = new RectangleF(-halfwidth * 2, pitchoffset, this.Width * 2, halfheight * 2 - pitchoffset); + + if (bg.Height != 0) + { + LinearGradientBrush linearBrush = new LinearGradientBrush(bg, Color.FromArgb(0x9b, 0xb8, 0x24), + Color.FromArgb(0x41, 0x4f, 0x07), LinearGradientMode.Vertical); + + graphicsObject.FillRectangle(linearBrush, bg); + } + + //draw centerline + graphicsObject.DrawLine(whitePen, -halfwidth * 2, pitchoffset + 0, halfwidth * 2, pitchoffset + 0); + } + + graphicsObject.ResetTransform(); + + graphicsObject.SetClip(new Rectangle(0, this.Height / 14, this.Width, this.Height - this.Height / 14)); + + graphicsObject.TranslateTransform(this.Width / 2, this.Height / 2); + graphicsObject.RotateTransform(-_roll); + + // draw armed + + if (status != statuslast) + { + armedtimer = DateTime.Now; + } + + if (status == 3) // not armed + { + //if ((armedtimer.AddSeconds(8) > DateTime.Now)) + { + drawstring(graphicsObject, "DISARMED", font, fontsize + 10, Brushes.Red, -85, halfheight / -3); + statuslast = status; + } + } + else if (status == 4) // armed + { + if ((armedtimer.AddSeconds(8) > DateTime.Now)) + { + drawstring(graphicsObject, "ARMED", font, fontsize + 20, Brushes.Red, -70, halfheight / -3); + statuslast = status; + } + } + + //draw pitch + + int lengthshort = this.Width / 12; + int lengthlong = this.Width / 8; + + for (int a = -90; a <= 90; a += 5) + { + // limit to 40 degrees + if (a >= _pitch - 34 && a <= _pitch + 25) + { + if (a % 10 == 0) + { + if (a == 0) + { + graphicsObject.DrawLine(greenPen, this.Width / 2 - lengthlong - halfwidth, pitchoffset + a * every5deg, this.Width / 2 + lengthlong - halfwidth, pitchoffset + a * every5deg); + } + else + { + graphicsObject.DrawLine(whitePen, this.Width / 2 - lengthlong - halfwidth, pitchoffset + a * every5deg, this.Width / 2 + lengthlong - halfwidth, pitchoffset + a * every5deg); + } + drawstring(graphicsObject, a.ToString(), font, fontsize + 2, whiteBrush, this.Width / 2 - lengthlong - 30 - halfwidth - (int)(fontoffset * 1.7), pitchoffset + a * every5deg - 8 - fontoffset); + } + else + { + graphicsObject.DrawLine(whitePen, this.Width / 2 - lengthshort - halfwidth, pitchoffset + a * every5deg, this.Width / 2 + lengthshort - halfwidth, pitchoffset + a * every5deg); + //drawstring(e,a.ToString(), new Font("Arial", 10), whiteBrush, this.Width / 2 - lengthshort - 20 - halfwidth, this.Height / 2 + pitchoffset + a * every5deg - 8); + } + } + } + + graphicsObject.ResetTransform(); + + // draw roll ind needle + + graphicsObject.TranslateTransform(this.Width / 2, this.Height / 2 + this.Height / 14); + + graphicsObject.RotateTransform(-_roll); + + Point[] pointlist = new Point[3]; + + lengthlong = this.Height / 66; + + int extra = this.Height / 15 * 7; + + pointlist[0] = new Point(0, -lengthlong * 2 - extra); + pointlist[1] = new Point(-lengthlong, -lengthlong - extra); + pointlist[2] = new Point(lengthlong, -lengthlong - extra); + + if (Math.Abs(_roll) > 45) + { + redPen.Width = 10; + } + + graphicsObject.DrawPolygon(redPen, pointlist); + + redPen.Width = 2; + + for (int a = -45; a <= 45; a += 15) + { + graphicsObject.ResetTransform(); + graphicsObject.TranslateTransform(this.Width / 2, this.Height / 2 + this.Height / 14); + graphicsObject.RotateTransform(a); + drawstring(graphicsObject, Math.Abs(a).ToString("##"), font, fontsize, whiteBrush, 0 - 6 - fontoffset, -lengthlong * 2 - extra); + graphicsObject.DrawLine(whitePen, 0, -halfheight, 0, -halfheight - 10); + } + + graphicsObject.ResetTransform(); + + //draw centre / current att + + Rectangle centercircle = new Rectangle(halfwidth - 10, halfheight - 10, 20, 20); + + graphicsObject.DrawEllipse(redPen, centercircle); + graphicsObject.DrawLine(redPen, centercircle.Left - 10, halfheight, centercircle.Left, halfheight); + graphicsObject.DrawLine(redPen, centercircle.Right, halfheight, centercircle.Right + 10, halfheight); + graphicsObject.DrawLine(redPen, centercircle.Left + centercircle.Width / 2, centercircle.Top, centercircle.Left + centercircle.Width / 2, centercircle.Top - 10); + + // draw roll ind + + Rectangle arcrect = new Rectangle(this.Width / 2 - this.Height / 2, this.Height / 14, this.Height, this.Height); + + graphicsObject.DrawArc(whitePen, arcrect, 180 + 45, 90); + + //draw heading ind + + graphicsObject.ResetClip(); + + Rectangle headbg = new Rectangle(0, 0, this.Width - 0, this.Height / 14); + + graphicsObject.DrawRectangle(blackPen, headbg); + + SolidBrush solidBrush = new SolidBrush(Color.FromArgb(0x55, 0xff, 0xff, 0xff)); + + graphicsObject.FillRectangle(solidBrush, headbg); + + // center + graphicsObject.DrawLine(redPen, headbg.Width / 2, headbg.Bottom, headbg.Width / 2, headbg.Top); + + //bottom line + graphicsObject.DrawLine(whitePen, headbg.Left + 5, headbg.Bottom - 5, headbg.Width - 5, headbg.Bottom - 5); + + float space = (headbg.Width - 10) / 60.0f; + int start = (int)Math.Round((_heading - 30),1); + + // draw for outside the 60 deg + if (_targetheading < start) + { + greenPen.Width = 6; + graphicsObject.DrawLine(greenPen, headbg.Left + 5 + space * 0, headbg.Bottom, headbg.Left + 5 + space * (0), headbg.Top); + } + if (_targetheading > _heading + 30) + { + greenPen.Width = 6; + graphicsObject.DrawLine(greenPen, headbg.Left + 5 + space * 60, headbg.Bottom, headbg.Left + 5 + space * (60), headbg.Top); + } + + for (int a = start; a <= _heading + 30; a += 1) + { + // target heading + if (((int)(a + 360) % 360) == (int)_targetheading) + { + greenPen.Width = 6; + graphicsObject.DrawLine(greenPen, headbg.Left + 5 + space * (a - start), headbg.Bottom, headbg.Left + 5 + space * (a - start), headbg.Top); + } + + if (((int)(a + 360) % 360) == (int)_groundcourse) + { + blackPen.Width = 6; + graphicsObject.DrawLine(blackPen, headbg.Left + 5 + space * (a - start), headbg.Bottom, headbg.Left + 5 + space * (a - start), headbg.Top); + blackPen.Width = 2; + } + + if ((int)a % 5 == 0) + { + //Console.WriteLine(a + " " + Math.Round(a, 1, MidpointRounding.AwayFromZero)); + //Console.WriteLine(space +" " + a +" "+ (headbg.Left + 5 + space * (a - start))); + graphicsObject.DrawLine(whitePen, headbg.Left + 5 + space * (a - start), headbg.Bottom - 5, headbg.Left + 5 + space * (a - start), headbg.Bottom - 10); + int disp = (int)a; + if (disp < 0) + disp += 360; + disp = disp % 360; + if (disp == 0) + { + drawstring(graphicsObject, "N".PadLeft(2), font, fontsize + 4, whiteBrush, headbg.Left - 5 + space * (a - start) - fontoffset, headbg.Bottom - 24 - (int)(fontoffset * 1.7)); + } + else if (disp == 90) + { + drawstring(graphicsObject, "E".PadLeft(2), font, fontsize + 4, whiteBrush, headbg.Left - 5 + space * (a - start) - fontoffset, headbg.Bottom - 24 - (int)(fontoffset * 1.7)); + } + else if (disp == 180) + { + drawstring(graphicsObject, "S".PadLeft(2), font, fontsize + 4, whiteBrush, headbg.Left - 5 + space * (a - start) - fontoffset, headbg.Bottom - 24 - (int)(fontoffset * 1.7)); + } + else if (disp == 270) + { + drawstring(graphicsObject, "W".PadLeft(2), font, fontsize + 4, whiteBrush, headbg.Left - 5 + space * (a - start) - fontoffset, headbg.Bottom - 24 - (int)(fontoffset * 1.7)); + } + else + { + drawstring(graphicsObject, (disp % 360).ToString().PadLeft(3), font, fontsize, whiteBrush, headbg.Left - 5 + space * (a - start) - fontoffset, headbg.Bottom - 24 - (int)(fontoffset * 1.7)); + } + } + } + + // Console.WriteLine("HUD 0 " + (DateTime.Now - starttime).TotalMilliseconds + " " + DateTime.Now.Millisecond); + + // xtrack error + // center + + float xtspace = this.Width / 10.0f / 3.0f; + int pad = 10; + + float myxtrack_error = _xtrack_error; + + myxtrack_error = Math.Min(myxtrack_error, 40); + myxtrack_error = Math.Max(myxtrack_error, -40); + + // xtrack - distance scale - space + float loc = myxtrack_error / 20.0f * xtspace; + + // current xtrack + if (Math.Abs(myxtrack_error) == 40) + { + greenPen.Color = Color.FromArgb(128, greenPen.Color); + } + + graphicsObject.DrawLine(greenPen, this.Width / 10 + loc, headbg.Bottom + 5, this.Width / 10 + loc, headbg.Bottom + this.Height / 10); + + greenPen.Color = Color.FromArgb(255, greenPen.Color); + + graphicsObject.DrawLine(whitePen, this.Width / 10, headbg.Bottom + 5, this.Width / 10, headbg.Bottom + this.Height / 10); + + graphicsObject.DrawLine(whitePen, this.Width / 10 - xtspace, headbg.Bottom + 5 + pad, this.Width / 10 - xtspace, headbg.Bottom + this.Height / 10 - pad); + + graphicsObject.DrawLine(whitePen, this.Width / 10 - xtspace * 2, headbg.Bottom + 5 + pad, this.Width / 10 - xtspace * 2, headbg.Bottom + this.Height / 10 - pad); + + graphicsObject.DrawLine(whitePen, this.Width / 10 + xtspace, headbg.Bottom + 5 + pad, this.Width / 10 + xtspace, headbg.Bottom + this.Height / 10 - pad); + + graphicsObject.DrawLine(whitePen, this.Width / 10 + xtspace * 2, headbg.Bottom + 5 + pad, this.Width / 10 + xtspace * 2, headbg.Bottom + this.Height / 10 - pad); + + // rate of turn + + whitePen.Width = 4; + graphicsObject.DrawLine(whitePen, this.Width / 10 - xtspace * 2 - xtspace / 2, headbg.Bottom + this.Height / 10 + 10, this.Width / 10 - xtspace * 2 - xtspace / 2 + xtspace, headbg.Bottom + this.Height / 10 + 10); + + graphicsObject.DrawLine(whitePen, this.Width / 10 - xtspace * 0 - xtspace / 2, headbg.Bottom + this.Height / 10 + 10, this.Width / 10 - xtspace * 0 - xtspace / 2 + xtspace, headbg.Bottom + this.Height / 10 + 10); + + graphicsObject.DrawLine(whitePen, this.Width / 10 + xtspace * 2 - xtspace / 2, headbg.Bottom + this.Height / 10 + 10, this.Width / 10 + xtspace * 2 - xtspace / 2 + xtspace, headbg.Bottom + this.Height / 10 + 10); + + float myturnrate = _turnrate; + float trwidth = (this.Width / 10 + xtspace * 2 - xtspace / 2) - (this.Width / 10 - xtspace * 2 - xtspace / 2); + + float range = 12; + + myturnrate = Math.Min(myturnrate, range / 2); + myturnrate = Math.Max(myturnrate, (range / 2) * -1.0f); + + loc = myturnrate / range * trwidth; + + greenPen.Width = 4; + + if (Math.Abs(myturnrate) == (range / 2)) + { + greenPen.Color = Color.FromArgb(128, greenPen.Color); + } + + graphicsObject.DrawLine(greenPen, this.Width / 10 + loc - xtspace / 2, headbg.Bottom + this.Height / 10 + 10 + 3, this.Width / 10 + loc + xtspace / 2, headbg.Bottom + this.Height / 10 + 10 + 3); + graphicsObject.DrawLine(greenPen, this.Width / 10 + loc, headbg.Bottom + this.Height / 10 + 10 + 3, this.Width / 10 + loc, headbg.Bottom + this.Height / 10 + 10 + 10); + + greenPen.Color = Color.FromArgb(255, greenPen.Color); + + whitePen.Width = 2; + + + + // left scroller + + Rectangle scrollbg = new Rectangle(0, halfheight - halfheight / 2, this.Width / 10, this.Height / 2); + + graphicsObject.DrawRectangle(whitePen, scrollbg); + + graphicsObject.FillRectangle(solidBrush, scrollbg); + + Point[] arrow = new Point[5]; + + arrow[0] = new Point(0, -10); + arrow[1] = new Point(scrollbg.Width - 10, -10); + arrow[2] = new Point(scrollbg.Width - 5, 0); + arrow[3] = new Point(scrollbg.Width - 10, 10); + arrow[4] = new Point(0, 10); + + graphicsObject.TranslateTransform(0, this.Height / 2); + + int viewrange = 26; + + float speed = _airspeed; + if (speed == 0) + speed = _groundspeed; + + space = (scrollbg.Height) / (float)viewrange; + start = ((int)speed - viewrange / 2); + + if (start > _targetspeed) + { + greenPen.Color = Color.FromArgb(128, greenPen.Color); + greenPen.Width = 6; + graphicsObject.DrawLine(greenPen, scrollbg.Left, scrollbg.Top, scrollbg.Left + scrollbg.Width, scrollbg.Top); + greenPen.Color = Color.FromArgb(255, greenPen.Color); + } + if ((speed + viewrange / 2) < _targetspeed) + { + greenPen.Color = Color.FromArgb(128, greenPen.Color); + greenPen.Width = 6; + graphicsObject.DrawLine(greenPen, scrollbg.Left, scrollbg.Top - space * viewrange, scrollbg.Left + scrollbg.Width, scrollbg.Top - space * viewrange); + greenPen.Color = Color.FromArgb(255, greenPen.Color); + } + + for (int a = (int)start; a <= (speed + viewrange / 2); a += 1) + { + if (a == (int)_targetspeed && _targetspeed != 0) + { + greenPen.Width = 6; + graphicsObject.DrawLine(greenPen, scrollbg.Left, scrollbg.Top - space * (a - start), scrollbg.Left + scrollbg.Width, scrollbg.Top - space * (a - start)); + } + if (a % 5 == 0) + { + //Console.WriteLine(a + " " + scrollbg.Right + " " + (scrollbg.Top - space * (a - start)) + " " + (scrollbg.Right - 20) + " " + (scrollbg.Top - space * (a - start))); + graphicsObject.DrawLine(whitePen, scrollbg.Right, scrollbg.Top - space * (a - start), scrollbg.Right - 10, scrollbg.Top - space * (a - start)); + drawstring(graphicsObject, a.ToString().PadLeft(5), font, fontsize, whiteBrush, scrollbg.Right - 50 - 4 * fontoffset, scrollbg.Top - space * (a - start) - 6 - fontoffset); + } + } + + graphicsObject.DrawPolygon(blackPen, arrow); + graphicsObject.FillPolygon(Brushes.Black, arrow); + drawstring(graphicsObject, ((int)speed).ToString("0"), font, 10, Brushes.AliceBlue, 0, -9); + + graphicsObject.ResetTransform(); + + // extra text data + + drawstring(graphicsObject, "AS " + _airspeed.ToString("0.0"), font, fontsize, whiteBrush, 1, scrollbg.Bottom + 5); + drawstring(graphicsObject, "GS " + _groundspeed.ToString("0.0"), font, fontsize, whiteBrush, 1, scrollbg.Bottom + fontsize + 2 + 10); + + //drawstring(e,, new Font("Arial", fontsize + 2), whiteBrush, 1, scrollbg.Bottom + fontsize + 2 + 10); + + // right scroller + + scrollbg = new Rectangle(this.Width - this.Width / 10, halfheight - halfheight / 2, this.Width / 10, this.Height / 2); + + graphicsObject.DrawRectangle(whitePen, scrollbg); + + graphicsObject.FillRectangle(solidBrush, scrollbg); + + arrow = new Point[5]; + + arrow[0] = new Point(0, -10); + arrow[1] = new Point(scrollbg.Width - 10, -10); + arrow[2] = new Point(scrollbg.Width - 5, 0); + arrow[3] = new Point(scrollbg.Width - 10, 10); + arrow[4] = new Point(0, 10); + + + + graphicsObject.TranslateTransform(0, this.Height / 2); + + + + + viewrange = 26; + + space = (scrollbg.Height) / (float)viewrange; + start = ((int)_alt - viewrange / 2); + + if (start > _targetalt) + { + greenPen.Color = Color.FromArgb(128, greenPen.Color); + greenPen.Width = 6; + graphicsObject.DrawLine(greenPen, scrollbg.Left, scrollbg.Top, scrollbg.Left + scrollbg.Width, scrollbg.Top); + greenPen.Color = Color.FromArgb(255, greenPen.Color); + } + if ((_alt + viewrange / 2) < _targetalt) + { + greenPen.Color = Color.FromArgb(128, greenPen.Color); + greenPen.Width = 6; + graphicsObject.DrawLine(greenPen, scrollbg.Left, scrollbg.Top - space * viewrange, scrollbg.Left + scrollbg.Width, scrollbg.Top - space * viewrange); + greenPen.Color = Color.FromArgb(255, greenPen.Color); + } + + for (int a = (int)start; a <= (_alt + viewrange / 2); a += 1) + { + if (a == Math.Round(_targetalt) && _targetalt != 0) + { + greenPen.Width = 6; + graphicsObject.DrawLine(greenPen, scrollbg.Left, scrollbg.Top - space * (a - start), scrollbg.Left + scrollbg.Width, scrollbg.Top - space * (a - start)); + } + if (a % 5 == 0) + { + //Console.WriteLine(a + " " + scrollbg.Left + " " + (scrollbg.Top - space * (a - start)) + " " + (scrollbg.Left + 20) + " " + (scrollbg.Top - space * (a - start))); + graphicsObject.DrawLine(whitePen, scrollbg.Left, scrollbg.Top - space * (a - start), scrollbg.Left + 10, scrollbg.Top - space * (a - start)); + drawstring(graphicsObject, a.ToString().PadLeft(5), font, fontsize, whiteBrush, scrollbg.Left + 7 + (int)(0 * fontoffset), scrollbg.Top - space * (a - start) - 6 - fontoffset); + } + } + + greenPen.Width = 4; + + // vsi + + graphicsObject.ResetTransform(); + + PointF[] poly = new PointF[4]; + + poly[0] = new PointF(scrollbg.Left, scrollbg.Top); + poly[1] = new PointF(scrollbg.Left - scrollbg.Width / 4, scrollbg.Top + scrollbg.Width / 4); + poly[2] = new PointF(scrollbg.Left - scrollbg.Width / 4, scrollbg.Bottom - scrollbg.Width / 4); + poly[3] = new PointF(scrollbg.Left, scrollbg.Bottom); + + //verticalspeed + + viewrange = 12; + + _verticalspeed = Math.Min(viewrange / 2, _verticalspeed); + _verticalspeed = Math.Max(viewrange / -2, _verticalspeed); + + float scaledvalue = _verticalspeed / -viewrange * (scrollbg.Bottom - scrollbg.Top); + + float linespace = (float)1 / -viewrange * (scrollbg.Bottom - scrollbg.Top); + + PointF[] polyn = new PointF[4]; + + polyn[0] = new PointF(scrollbg.Left, scrollbg.Top + (scrollbg.Bottom - scrollbg.Top) / 2); + polyn[1] = new PointF(scrollbg.Left - scrollbg.Width / 4, scrollbg.Top + (scrollbg.Bottom - scrollbg.Top) / 2); + polyn[2] = polyn[1]; + float peak = 0; + if (scaledvalue > 0) + { + peak = -scrollbg.Width / 4; + if (scrollbg.Top + (scrollbg.Bottom - scrollbg.Top) / 2 + scaledvalue + peak < scrollbg.Top + (scrollbg.Bottom - scrollbg.Top) / 2) + peak = -scaledvalue; + } + else if (scaledvalue < 0) + { + peak = +scrollbg.Width / 4; + if (scrollbg.Top + (scrollbg.Bottom - scrollbg.Top) / 2 + scaledvalue + peak > scrollbg.Top + (scrollbg.Bottom - scrollbg.Top) / 2) + peak = -scaledvalue; + } + + polyn[2] = new PointF(scrollbg.Left - scrollbg.Width / 4, scrollbg.Top + (scrollbg.Bottom - scrollbg.Top) / 2 + scaledvalue + peak); + polyn[3] = new PointF(scrollbg.Left, scrollbg.Top + (scrollbg.Bottom - scrollbg.Top) / 2 + scaledvalue); + + //graphicsObject.DrawPolygon(redPen, poly); + graphicsObject.FillPolygon(Brushes.Blue, polyn); + + // draw outsidebox + graphicsObject.DrawPolygon(whitePen, poly); + + for (int a = 1; a < viewrange; a++) + { + graphicsObject.DrawLine(whitePen, scrollbg.Left - scrollbg.Width / 4, scrollbg.Top - linespace * a, scrollbg.Left - scrollbg.Width / 8, scrollbg.Top - linespace * a); + } + + // draw arrow and text + + graphicsObject.ResetTransform(); + graphicsObject.TranslateTransform(this.Width, this.Height / 2); + graphicsObject.RotateTransform(180); + + graphicsObject.DrawPolygon(blackPen, arrow); + graphicsObject.FillPolygon(Brushes.Black, arrow); + graphicsObject.ResetTransform(); + graphicsObject.TranslateTransform(0, this.Height / 2); + + drawstring(graphicsObject, ((int)_alt).ToString("0"), font, 10, Brushes.AliceBlue, scrollbg.Left + 10, -9); + graphicsObject.ResetTransform(); + + // mode and wp dist and wp + + drawstring(graphicsObject, _mode, font, fontsize, whiteBrush, scrollbg.Left - 30, scrollbg.Bottom + 5); + drawstring(graphicsObject, (int)_disttowp + ">" + _wpno, font, fontsize, whiteBrush, scrollbg.Left - 30, scrollbg.Bottom + fontsize + 2 + 10); + + graphicsObject.DrawLine(greenPen, scrollbg.Left - 5, scrollbg.Top - (int)(fontsize * 2.2) - 2 - 20, scrollbg.Left - 5, scrollbg.Top - (int)(fontsize) - 2 - 20); + graphicsObject.DrawLine(greenPen, scrollbg.Left - 10, scrollbg.Top - (int)(fontsize * 2.2) - 2 - 15, scrollbg.Left - 10, scrollbg.Top - (int)(fontsize) - 2 - 20); + graphicsObject.DrawLine(greenPen, scrollbg.Left - 15, scrollbg.Top - (int)(fontsize * 2.2) - 2 - 10, scrollbg.Left - 15, scrollbg.Top - (int)(fontsize ) - 2 - 20); + + drawstring(graphicsObject, _linkqualitygcs.ToString("0") + "%", font, fontsize, whiteBrush, scrollbg.Left, scrollbg.Top - (int)(fontsize * 2.2) - 2 - 20); + if (_linkqualitygcs == 0) + { + graphicsObject.DrawLine(redPen, scrollbg.Left, scrollbg.Top - (int)(fontsize * 2.2) - 2 - 20, scrollbg.Left + 50, scrollbg.Top - (int)(fontsize * 2.2) - 2); + + graphicsObject.DrawLine(redPen, scrollbg.Left, scrollbg.Top - (int)(fontsize * 2.2) - 2, scrollbg.Left + 50, scrollbg.Top - (int)(fontsize * 2.2) - 2 - 20); + } + drawstring(graphicsObject, _datetime.ToString("HH:mm:ss"), font, fontsize, whiteBrush, scrollbg.Left - 20, scrollbg.Top - fontsize - 2 - 20); + + + // battery + + graphicsObject.ResetTransform(); + + drawstring(graphicsObject, "Bat", font, fontsize + 2, whiteBrush, fontsize, this.Height - 30 - fontoffset); + drawstring(graphicsObject, _batterylevel.ToString("0.00v"), font, fontsize + 2, whiteBrush, fontsize * 4, this.Height - 30 - fontoffset); + drawstring(graphicsObject, _batteryremaining.ToString("0%"), font, fontsize + 2, whiteBrush, fontsize * 9, this.Height - 30 - fontoffset); + + // gps + + string gps = ""; + + if (_gpsfix == 0) + { + gps = ("GPS: No GPS"); + } + else if (_gpsfix == 1) + { + gps = ("GPS: No Fix"); + } + else if (_gpsfix == 2) + { + gps = ("GPS: 3D Fix"); + } + else if (_gpsfix == 3) + { + gps = ("GPS: 3D Fix"); + } + + drawstring(graphicsObject, gps, font, fontsize + 2, whiteBrush, this.Width - 10 * fontsize, this.Height - 30 - fontoffset); + + + if (isNaN) + drawstring(graphicsObject, "NaN Error " + DateTime.Now, font, this.Height / 30 + 10, Brushes.Red, 50, 50); + + + if (!opengl) + { + e.Graphics.DrawImageUnscaled(objBitmap, 0, 0); + } + + if (DesignMode) + { + return; + } + + // Console.WriteLine("HUD 1 " + (DateTime.Now - starttime).TotalMilliseconds + " " + DateTime.Now.Millisecond); + + ImageCodecInfo ici = GetImageCodec("image/jpeg"); + EncoderParameters eps = new EncoderParameters(1); + eps.Param[0] = new EncoderParameter(System.Drawing.Imaging.Encoder.Quality, 50L); // or whatever other quality value you want + + lock (streamlock) + { + if (streamjpgenable || streamjpg == null) // init image and only update when needed + { + if (opengl) + { + objBitmap = GrabScreenshot(); + } + streamjpg = new MemoryStream(); + objBitmap.Save(streamjpg, ici, eps); + //objBitmap.Save(streamjpg,ImageFormat.Bmp); + } + } + } + catch (Exception ex) + { + log.Info("hud error "+ex.ToString()); + } + } + + protected override void OnPaintBackground(PaintEventArgs e) + { + //base.OnPaintBackground(e); + } + + ImageCodecInfo GetImageCodec(string mimetype) + { + foreach (ImageCodecInfo ici in ImageCodecInfo.GetImageEncoders()) + { + if (ici.MimeType == mimetype) return ici; + } + return null; + } + + // Returns a System.Drawing.Bitmap with the contents of the current framebuffer + public new Bitmap GrabScreenshot() + { + if (GraphicsContext.CurrentContext == null) + throw new GraphicsContextMissingException(); + + Bitmap bmp = new Bitmap(this.ClientSize.Width, this.ClientSize.Height); + System.Drawing.Imaging.BitmapData data = + bmp.LockBits(this.ClientRectangle, System.Drawing.Imaging.ImageLockMode.WriteOnly, System.Drawing.Imaging.PixelFormat.Format24bppRgb); + GL.ReadPixels(0, 0, this.ClientSize.Width, this.ClientSize.Height,OpenTK.Graphics.OpenGL.PixelFormat.Bgr, PixelType.UnsignedByte, data.Scan0); + bmp.UnlockBits(data); + + bmp.RotateFlip(RotateFlipType.RotateNoneFlipY); + return bmp; + } + + + float wrap360(float noin) + { + if (noin < 0) + return noin + 360; + return noin; + } + + /// <summary> + /// pen for drawstring + /// </summary> + Pen P = new Pen(Color.FromArgb(0x26, 0x27, 0x28), 2f); + /// <summary> + /// pth for drawstring + /// </summary> + GraphicsPath pth = new GraphicsPath(); + + void drawstring(HUD e, string text, Font font, float fontsize, Brush brush, float x, float y) + { + if (!opengl) + { + drawstring(graphicsObjectGDIP, text, font, fontsize, brush, x, y); + return; + } + + if (text == null || text == "") + return; + /* + OpenTK.Graphics.Begin(); + GL.PushMatrix(); + GL.Translate(x, y, 0); + printer.Print(text, font, c); + GL.PopMatrix(); printer.End(); + */ + + char[] chars = text.ToCharArray(); + + float maxy = 1; + + foreach (char cha in chars) + { + int charno = (int)cha; + + int charid = charno + (128 * (int)fontsize); // 128 * 40 * 5;128 + + if (charbitmaps[charid] == null) + { + charbitmaps[charid] = new Bitmap(128, 128, System.Drawing.Imaging.PixelFormat.Format32bppArgb); + + charbitmaps[charid].MakeTransparent(Color.Transparent); + + //charbitmaptexid + + float maxx = this.Width / 150; // for space + + + // create bitmap + using (Graphics gfx = Graphics.FromImage(charbitmaps[charid])) + { + pth.Reset(); + + if (text != null) + pth.AddString(cha + "", font.FontFamily, 0, fontsize + 5, new Point((int)0, (int)0), StringFormat.GenericTypographic); + + gfx.SmoothingMode = System.Drawing.Drawing2D.SmoothingMode.AntiAlias; + + gfx.DrawPath(P, pth); + + //Draw the face + + gfx.FillPath(brush, pth); + + + if (pth.PointCount > 0) + { + foreach (PointF pnt in pth.PathPoints) + { + if (pnt.X > maxx) + maxx = pnt.X; + + if (pnt.Y > maxy) + maxy = pnt.Y; + } + } + } + + charwidth[charid] = (int)(maxx + 2); + + //charbitmaps[charid] = charbitmaps[charid].Clone(new RectangleF(0, 0, maxx + 2, maxy + 2), charbitmaps[charid].PixelFormat); + + //charbitmaps[charno * (int)fontsize].Save(charno + " " + (int)fontsize + ".png"); + + // create texture + int textureId; + GL.TexEnv(TextureEnvTarget.TextureEnv, TextureEnvParameter.TextureEnvMode, (float)TextureEnvModeCombine.Replace);//Important, or wrong color on some computers + + Bitmap bitmap = charbitmaps[charid]; + GL.GenTextures(1, out textureId); + GL.BindTexture(TextureTarget.Texture2D, textureId); + + BitmapData data = bitmap.LockBits(new System.Drawing.Rectangle(0, 0, bitmap.Width, bitmap.Height), ImageLockMode.ReadOnly, System.Drawing.Imaging.PixelFormat.Format32bppArgb); + + GL.TexImage2D(TextureTarget.Texture2D, 0, PixelInternalFormat.Rgba, data.Width, data.Height, 0, OpenTK.Graphics.OpenGL.PixelFormat.Bgra, PixelType.UnsignedByte, data.Scan0); + + GL.TexParameter(TextureTarget.Texture2D, TextureParameterName.TextureMinFilter, (int)TextureMinFilter.Linear); + GL.TexParameter(TextureTarget.Texture2D, TextureParameterName.TextureMagFilter, (int)TextureMagFilter.Linear); + + // GL.TexParameter(TextureTarget.Texture2D, TextureParameterName.TextureMagFilter, (int)All.Nearest); + //GL.TexParameter(TextureTarget.Texture2D, TextureParameterName.TextureMinFilter, (int)All.Nearest); + GL.Finish(); + bitmap.UnlockBits(data); + + charbitmaptexid[charid] = textureId; + } + + //GL.Enable(EnableCap.Blend); + GL.BlendFunc(BlendingFactorSrc.SrcAlpha, BlendingFactorDest.OneMinusSrcAlpha); + + GL.Enable(EnableCap.Texture2D); + GL.BindTexture(TextureTarget.Texture2D, charbitmaptexid[charid]); + + float scale = 1.0f; + + GL.Begin(BeginMode.Quads); + GL.TexCoord2(0, 0); GL.Vertex2(x, y); + GL.TexCoord2(1, 0); GL.Vertex2(x + charbitmaps[charid].Width * scale, y); + GL.TexCoord2(1, 1); GL.Vertex2(x + charbitmaps[charid].Width * scale, y + charbitmaps[charid].Height * scale); + GL.TexCoord2(0, 1); GL.Vertex2(x + 0, y + charbitmaps[charid].Height * scale); + GL.End(); + + //GL.Disable(EnableCap.Blend); + GL.Disable(EnableCap.Texture2D); + + x += charwidth[charid] * scale; + } + } + + void drawstring(Graphics e, string text, Font font, float fontsize, Brush brush, float x, float y) + { + if (text == null || text == "") + return; + + pth.Reset(); + + if (text != null) + pth.AddString(text, font.FontFamily, 0, fontsize + 5, new Point((int)x, (int)y), StringFormat.GenericTypographic); + + //Draw the edge + // this uses lots of cpu time + + //e.SmoothingMode = SmoothingMode.HighSpeed; + + if (e == null || P == null || pth == null || pth.PointCount == 0) + return; + + //if (!ArdupilotMega.MainV2.MONO) + e.DrawPath(P, pth); + + //Draw the face + + e.FillPath(brush, pth); + + //pth.Dispose(); + } + + protected override void OnHandleCreated(EventArgs e) + { + try + { + if (opengl) + { + base.OnHandleCreated(e); + } + } + catch (Exception ex) { log.Info(ex.ToString()); opengl = false; } // macs fail here + } + + protected override void OnHandleDestroyed(EventArgs e) + { + try + { + if (opengl) + { + base.OnHandleDestroyed(e); + } + } + catch (Exception ex) { log.Info(ex.ToString()); opengl = false; } + } + + protected override void OnResize(EventArgs e) + { + if (DesignMode || !started) + return; + + + if (SixteenXNine) + { + this.Height = (int)(this.Width / 1.777f); + } + else + { + // 4x3 + this.Height = (int)(this.Width / 1.333f); + } + + base.OnResize(e); + + graphicsObjectGDIP = Graphics.FromImage(objBitmap); + + charbitmaps = new Bitmap[charbitmaps.Length]; + + try + { + if (opengl) + { + foreach (int texid in charbitmaptexid) + { + if (texid != 0) + GL.DeleteTexture(texid); + } + } + } + catch { } + + GC.Collect(); + + try + { + if (opengl) + { + GL.MatrixMode(MatrixMode.Projection); + GL.LoadIdentity(); + GL.Ortho(0, Width, Height, 0, -1, 1); + GL.MatrixMode(MatrixMode.Modelview); + GL.LoadIdentity(); + + GL.Viewport(0, 0, Width, Height); + } + } + catch { } + + } + } } \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/Controls/ImageLabel.Designer.cs b/Tools/ArdupilotMegaPlanner/Controls/ImageLabel.Designer.cs index dfa1e43a2dd8d01a5c5d445b7d4cd2a49be40b74..fa42576c8c5f8a5146fd608ae204bc60e154d8f5 100644 --- a/Tools/ArdupilotMegaPlanner/Controls/ImageLabel.Designer.cs +++ b/Tools/ArdupilotMegaPlanner/Controls/ImageLabel.Designer.cs @@ -1,4 +1,4 @@ -namespace ArdupilotMega +namespace ArdupilotMega.Controls { partial class ImageLabel { diff --git a/Tools/ArdupilotMegaPlanner/Controls/ImageLabel.cs b/Tools/ArdupilotMegaPlanner/Controls/ImageLabel.cs index 2b16d6337d72d13bc10383adbbad3fcdc528afe8..1cd32b95c3fef2455cf35fe6186b1da00f0096ce 100644 --- a/Tools/ArdupilotMegaPlanner/Controls/ImageLabel.cs +++ b/Tools/ArdupilotMegaPlanner/Controls/ImageLabel.cs @@ -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 { diff --git a/Tools/ArdupilotMegaPlanner/Controls/LineSeparator.cs b/Tools/ArdupilotMegaPlanner/Controls/LineSeparator.cs index 9e9002a87557157c36075af36c3707c7924b9ca4..5c96aff3e4c3613f41bdf7e821040e3eb7438913 100644 --- a/Tools/ArdupilotMegaPlanner/Controls/LineSeparator.cs +++ b/Tools/ArdupilotMegaPlanner/Controls/LineSeparator.cs @@ -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) - { + private void LineSeparator_Paint(object sender, PaintEventArgs e) + { - Graphics g = e.Graphics; + Graphics g = e.Graphics; - g.DrawLine( + g.DrawLine( - Pens.DarkGray, new Point(0, 0), new Point(this.Width, 0)); + Pens.DarkGray, new Point(0, 0), new Point(this.Width, 0)); - g.DrawLine( + g.DrawLine( - Pens.White, new Point(0, 1), new Point(this.Width, 1)); + Pens.White, new Point(0, 1), new Point(this.Width, 1)); - } + } -} + } +} \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/Controls/MyButton.cs b/Tools/ArdupilotMegaPlanner/Controls/MyButton.cs index 9faaeb84419e1c2a6f08f1bc8e81c0f533ab19d4..05167056455c79cadaa56315de9b12905af15cc8 100644 --- a/Tools/ArdupilotMegaPlanner/Controls/MyButton.cs +++ b/Tools/ArdupilotMegaPlanner/Controls/MyButton.cs @@ -10,7 +10,7 @@ using System.Windows.Forms; using System.Drawing.Drawing2D; -namespace ArdupilotMega +namespace ArdupilotMega.Controls { class MyButton : Button { diff --git a/Tools/ArdupilotMegaPlanner/Controls/MyLabel.cs b/Tools/ArdupilotMegaPlanner/Controls/MyLabel.cs index cc18c0b72358d8f5a099855472a94b2e90671ccc..b2a931d4bf344e53aed57fb61ef5ec3bcecf9989 100644 --- a/Tools/ArdupilotMegaPlanner/Controls/MyLabel.cs +++ b/Tools/ArdupilotMegaPlanner/Controls/MyLabel.cs @@ -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 { diff --git a/Tools/ArdupilotMegaPlanner/Controls/MyTrackBar.cs b/Tools/ArdupilotMegaPlanner/Controls/MyTrackBar.cs index 1e010c806b032da309596585658d71ddf95a545c..bf4536df0f31e99e27744d86f86b66595dd70812 100644 --- a/Tools/ArdupilotMegaPlanner/Controls/MyTrackBar.cs +++ b/Tools/ArdupilotMegaPlanner/Controls/MyTrackBar.cs @@ -4,7 +4,7 @@ using System.Linq; using System.Text; using System.Windows.Forms; -namespace ArdupilotMega +namespace ArdupilotMega.Controls { class MyTrackBar : TrackBar { diff --git a/Tools/ArdupilotMegaPlanner/Controls/MyUserControl.cs b/Tools/ArdupilotMegaPlanner/Controls/MyUserControl.cs index 0a7a76479355c6d666a28be965265c6b1816cb8f..58260f138be2b86002eeb8b145baebc6daef2efa 100644 --- a/Tools/ArdupilotMegaPlanner/Controls/MyUserControl.cs +++ b/Tools/ArdupilotMegaPlanner/Controls/MyUserControl.cs @@ -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) diff --git a/Tools/ArdupilotMegaPlanner/Controls/ProgressReporterDialogue.cs b/Tools/ArdupilotMegaPlanner/Controls/ProgressReporterDialogue.cs index 683b995004cbd18497954209e8ae2b0e165fdba3..ff11f878deda7b3c4329ac4dbb89aec5e0f9ea06 100644 --- a/Tools/ArdupilotMegaPlanner/Controls/ProgressReporterDialogue.cs +++ b/Tools/ArdupilotMegaPlanner/Controls/ProgressReporterDialogue.cs @@ -5,8 +5,6 @@ using System.Windows.Forms; namespace ArdupilotMega.Controls { - - /// <summary> /// Form that is shown to the user during a background operation /// </summary> diff --git a/Tools/ArdupilotMegaPlanner/Controls/XorPlus.Designer.cs b/Tools/ArdupilotMegaPlanner/Controls/XorPlus.Designer.cs deleted file mode 100644 index 2a14e1fe1f23560109de7669b4951eee32672c81..0000000000000000000000000000000000000000 --- a/Tools/ArdupilotMegaPlanner/Controls/XorPlus.Designer.cs +++ /dev/null @@ -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; - } -} diff --git a/Tools/ArdupilotMegaPlanner/Controls/XorPlus.cs b/Tools/ArdupilotMegaPlanner/Controls/XorPlus.cs deleted file mode 100644 index 98808fe43295b1b0227340bc98050f34562c5ba7..0000000000000000000000000000000000000000 --- a/Tools/ArdupilotMegaPlanner/Controls/XorPlus.cs +++ /dev/null @@ -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(); - } - } -} diff --git a/Tools/ArdupilotMegaPlanner/Controls/XorPlus.resx b/Tools/ArdupilotMegaPlanner/Controls/XorPlus.resx deleted file mode 100644 index 7080a7d118e8cd7ec668e9bb0d8e90767e0c7a3c..0000000000000000000000000000000000000000 --- a/Tools/ArdupilotMegaPlanner/Controls/XorPlus.resx +++ /dev/null @@ -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> \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/Controls/myGMAP.cs b/Tools/ArdupilotMegaPlanner/Controls/myGMAP.cs index 38e37a84be36ece4f7ab1f7f62ad892f863dcbf3..f24440fb59e4be8f816f5f2f3976efb01d4c6c43 100644 --- a/Tools/ArdupilotMegaPlanner/Controls/myGMAP.cs +++ b/Tools/ArdupilotMegaPlanner/Controls/myGMAP.cs @@ -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; diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/Configuration.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/Configuration.Designer.cs index 50e01de71c5e89fe649bf489dc67d7702d2053b6..a9966cb926aa69fab7f1d16fbd4c6ac068cc9bdb 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/Configuration.Designer.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/Configuration.Designer.cs @@ -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; diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/Configuration.cs b/Tools/ArdupilotMegaPlanner/GCSViews/Configuration.cs index fd5a942cdad3f0740f276a02db65d3f526070177..6d3ff562e174c6fd0a6f7277c167fefcdfc9dd37 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/Configuration.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/Configuration.cs @@ -13,6 +13,7 @@ using System.Globalization; using System.Threading; using DirectShowLib; using System.Runtime.InteropServices; +using ArdupilotMega.Controls; namespace ArdupilotMega.GCSViews { diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/Configuration.resx b/Tools/ArdupilotMegaPlanner/GCSViews/Configuration.resx index 7f73de58f983e67c8bbf8f6d25328a114f6bcba4..8aed12b21074b823c93f0497f64bd9cd0d9266d7 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/Configuration.resx +++ b/Tools/ArdupilotMegaPlanner/GCSViews/Configuration.resx @@ -367,7 +367,7 @@ <value>myLabel2</value> </data> <data name=">>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=">>myLabel2.Parent" xml:space="preserve"> <value>groupBox17</value> @@ -379,7 +379,7 @@ <value>myLabel4</value> </data> <data name=">>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=">>myLabel4.Parent" xml:space="preserve"> <value>groupBox17</value> @@ -403,7 +403,7 @@ <value>myLabel3</value> </data> <data name=">>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=">>myLabel3.Parent" xml:space="preserve"> <value>groupBox17</value> @@ -415,7 +415,7 @@ <value>myLabel1</value> </data> <data name=">>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=">>myLabel1.Parent" xml:space="preserve"> <value>groupBox17</value> @@ -2341,7 +2341,7 @@ <value>BUT_Joystick</value> </data> <data name=">>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=">>BUT_Joystick.Parent" xml:space="preserve"> <value>TabPlanner</value> @@ -2353,7 +2353,7 @@ <value>BUT_videostop</value> </data> <data name=">>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=">>BUT_videostop.Parent" xml:space="preserve"> <value>TabPlanner</value> @@ -2365,7 +2365,7 @@ <value>BUT_videostart</value> </data> <data name=">>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=">>BUT_videostart.Parent" xml:space="preserve"> <value>TabPlanner</value> @@ -5926,7 +5926,7 @@ <value>myLabel4</value> </data> <data name=">>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=">>myLabel4.Parent" xml:space="preserve"> <value>groupBox17</value> @@ -5950,7 +5950,7 @@ <value>myLabel3</value> </data> <data name=">>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=">>myLabel3.Parent" xml:space="preserve"> <value>groupBox17</value> @@ -6016,7 +6016,7 @@ <value>myLabel2</value> </data> <data name=">>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=">>myLabel2.Parent" xml:space="preserve"> <value>groupBox17</value> @@ -6127,7 +6127,7 @@ <value>myLabel1</value> </data> <data name=">>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=">>myLabel1.Parent" xml:space="preserve"> <value>groupBox17</value> @@ -9018,7 +9018,7 @@ GDI+ = Enabled</value> <value>BUT_Joystick</value> </data> <data name=">>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=">>BUT_Joystick.Parent" xml:space="preserve"> <value>TabPlanner</value> @@ -9045,7 +9045,7 @@ GDI+ = Enabled</value> <value>BUT_videostop</value> </data> <data name=">>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=">>BUT_videostop.Parent" xml:space="preserve"> <value>TabPlanner</value> @@ -9072,7 +9072,7 @@ GDI+ = Enabled</value> <value>BUT_videostart</value> </data> <data name=">>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=">>BUT_videostart.Parent" xml:space="preserve"> <value>TabPlanner</value> @@ -9120,7 +9120,7 @@ GDI+ = Enabled</value> <value>BUT_rerequestparams</value> </data> <data name=">>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=">>BUT_rerequestparams.Parent" xml:space="preserve"> <value>$this</value> @@ -9153,7 +9153,7 @@ GDI+ = Enabled</value> <value>BUT_writePIDS</value> </data> <data name=">>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=">>BUT_writePIDS.Parent" xml:space="preserve"> <value>$this</value> @@ -9189,7 +9189,7 @@ GDI+ = Enabled</value> <value>BUT_save</value> </data> <data name=">>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=">>BUT_save.Parent" xml:space="preserve"> <value>$this</value> @@ -9225,7 +9225,7 @@ GDI+ = Enabled</value> <value>BUT_load</value> </data> <data name=">>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=">>BUT_load.Parent" xml:space="preserve"> <value>$this</value> @@ -9258,7 +9258,7 @@ GDI+ = Enabled</value> <value>BUT_compare</value> </data> <data name=">>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=">>BUT_compare.Parent" xml:space="preserve"> <value>$this</value> diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibrationPlane.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibrationPlane.Designer.cs index e674259f9122277ee40051dc8c2cd82a0a7bb5bf..c3ddcee8a45682d0b0d110bd3b8fca365ca6d4fd 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibrationPlane.Designer.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibrationPlane.Designer.cs @@ -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; diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibrationPlane.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibrationPlane.cs index 6837cc9ce3c0c72a22e9bfaa76f38fec85e225b6..5c08a8ab7edc7a774bf628e48dc8612713f05243 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibrationPlane.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibrationPlane.cs @@ -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 { diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibrationPlane.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibrationPlane.resx index a4f7288080463d18d246ff455416ec247da02ced..062a6b34a52f2a97e161a4f3a44743722d8109ff 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibrationPlane.resx +++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibrationPlane.resx @@ -175,7 +175,7 @@ <value>BUT_levelplane</value> </data> <data name=">>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=">>BUT_levelplane.Parent" xml:space="preserve"> <value>$this</value> diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibrationQuad.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibrationQuad.Designer.cs index 823abeb9abc2931cf1ae80bd8672ef824582b4ef..b9e95dff5a79dce218f45f42acd59e15b0fefae4 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibrationQuad.Designer.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibrationQuad.Designer.cs @@ -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; diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibrationQuad.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibrationQuad.cs index 5da92ae68d61e27cfb4b013a6068ccea0a4b06d9..7cc693578def855ccd9faaeced9535691e6fc8f8 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibrationQuad.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibrationQuad.cs @@ -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 { diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibrationQuad.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibrationQuad.resx index fafc62b415747875244e6c12cc83371240d1de8d..d21598f126ca8e9ac66b973122878dd8dbbbdfca 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibrationQuad.resx +++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibrationQuad.resx @@ -250,7 +250,7 @@ <value>BUT_levelac2</value> </data> <data name=">>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=">>BUT_levelac2.Parent" xml:space="preserve"> <value>$this</value> diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArducopter.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArducopter.Designer.cs index a67ec30bdb6fc87700376076a3d6289b892c33b4..ec5d7ca2cf8a0bf66fe9c671e75f14e1abbe437e 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArducopter.Designer.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArducopter.Designer.cs @@ -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; diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArducopter.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArducopter.cs index 606a5f34d42c32dc19cd940e66647db38d0e4ac7..ce263e44ccd961fd4500fa6ed884b98f380a1c8e 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArducopter.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArducopter.cs @@ -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 { diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArducopter.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArducopter.resx index 1be2fe2b20058b2f6d19ea8def6842eb04f6d2b7..c404907f7dc5b1aab79b897794cef8b67a6419cd 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArducopter.resx +++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArducopter.resx @@ -135,7 +135,7 @@ <value>myLabel3</value> </data> <data name=">>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=">>myLabel3.Parent" xml:space="preserve"> <value>$this</value> @@ -201,7 +201,7 @@ <value>myLabel2</value> </data> <data name=">>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=">>myLabel2.Parent" xml:space="preserve"> <value>$this</value> @@ -312,7 +312,7 @@ <value>myLabel1</value> </data> <data name=">>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=">>myLabel1.Parent" xml:space="preserve"> <value>$this</value> diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArduplane.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArduplane.cs index 34afb1dc4c35063fa6fffebe77091856f654c93d..11bbb4fb8e4bff14e627a966f14e1ab6ec98c7c8 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArduplane.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArduplane.cs @@ -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 { diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigBatteryMonitoring.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigBatteryMonitoring.cs index d84fe9af39df8d0d32c21866fa1c9ecf778bf370..404f48b8449cb1ae9f8df1ab43b06cf6bd863e78 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigBatteryMonitoring.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigBatteryMonitoring.cs @@ -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 { diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFlightModes.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFlightModes.Designer.cs index ed3be8b2237a95313d34586f58633ed2f8204181..a9c3c3d3247cf7b19ed92af7835d8aa37b6abf89 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFlightModes.Designer.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFlightModes.Designer.cs @@ -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; } } diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFlightModes.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFlightModes.cs index a19aa5c2500a54af323687d2b671b89c0e228b31..3e89a13282bb453d12f5edb20be6db1adbfd50bf 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFlightModes.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFlightModes.cs @@ -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 { diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFlightModes.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFlightModes.resx index 7f2a0fb988e67c2f21b856f04036e1cc20582504..5fe9928d4b221a9fb9e6be0eaee6875dececd86e 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFlightModes.resx +++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFlightModes.resx @@ -946,7 +946,7 @@ <value>BUT_SaveModes</value> </data> <data name=">>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=">>BUT_SaveModes.Parent" xml:space="preserve"> <value>$this</value> diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigHardwareOptions.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigHardwareOptions.Designer.cs index e5a2e07eae8804d8d4759af95fd8128adb4c0ee8..dedab86cf263fb8b391bfb474cec5940c670e34b 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigHardwareOptions.Designer.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigHardwareOptions.Designer.cs @@ -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; } } diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigHardwareOptions.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigHardwareOptions.cs index e804b8052970a685cd3300e166d5a325cb7bcb70..b9795fb111e3fe2ca0806b9f0247137c5d423f74 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigHardwareOptions.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigHardwareOptions.cs @@ -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 { diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigHardwareOptions.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigHardwareOptions.resx index b15fe2836a3805faf4f5ae2f2affb5ed313a2566..64dab98e71de3185c3e679bcd28e3a8891217565 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigHardwareOptions.resx +++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigHardwareOptions.resx @@ -139,7 +139,7 @@ <value>BUT_MagCalibrationLive</value> </data> <data name=">>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=">>BUT_MagCalibrationLive.Parent" xml:space="preserve"> <value>$this</value> @@ -526,7 +526,7 @@ <value>BUT_MagCalibrationLog</value> </data> <data name=">>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=">>BUT_MagCalibrationLog.Parent" xml:space="preserve"> <value>$this</value> diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigPlanner.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigPlanner.Designer.cs index 3b6108454fd4a2ae5076634b44bc72db7cd0a511..2bd40512120e3665f29ab2482ea20c0acab0fb3b 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigPlanner.Designer.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigPlanner.Designer.cs @@ -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; } } diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigPlanner.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigPlanner.cs index 3e35ec89ce9d060608c6653ef628e6fc72182ff6..11e3e4a01ef93e7f1c544f2633454ea295970915 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigPlanner.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigPlanner.cs @@ -10,6 +10,7 @@ using System.Text; using System.Windows.Forms; using DirectShowLib; using ArdupilotMega.Controls.BackstageView; +using ArdupilotMega.Controls; namespace ArdupilotMega.GCSViews.ConfigurationView { diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigPlanner.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigPlanner.resx index 6e758040783b8ce005ca91e5ddca45cf3502c06d..8e15fbeacfbce438fcbbc35ad7480d9a862be90c 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigPlanner.resx +++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigPlanner.resx @@ -1268,7 +1268,7 @@ <value>BUT_Joystick</value> </data> <data name=">>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=">>BUT_Joystick.Parent" xml:space="preserve"> <value>$this</value> @@ -1295,7 +1295,7 @@ <value>BUT_videostop</value> </data> <data name=">>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=">>BUT_videostop.Parent" xml:space="preserve"> <value>$this</value> @@ -1322,7 +1322,7 @@ <value>BUT_videostart</value> </data> <data name=">>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=">>BUT_videostart.Parent" xml:space="preserve"> <value>$this</value> diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRadioInput.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRadioInput.Designer.cs index f3e54cffe31d01144b2001ac5dcbe644f903340e..2ef80c22adfc1a19ae214c83d92df0280d3ad099 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRadioInput.Designer.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRadioInput.Designer.cs @@ -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; diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRadioInput.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRadioInput.cs index 91e6716fe9283c875a43b0715c416f1250124e2e..1cf26eacaff532b16ee1af4111f87c98feb77898 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRadioInput.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRadioInput.cs @@ -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 { diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRadioInput.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRadioInput.resx index f4c0f26f3b53c9d87c859e5fd9a61ac26872785c..55749712e8fce260345ae977ed2507625f344972 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRadioInput.resx +++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRadioInput.resx @@ -403,7 +403,7 @@ <value>BUT_Calibrateradio</value> </data> <data name=">>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=">>BUT_Calibrateradio.Parent" xml:space="preserve"> <value>$this</value> diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRawParams.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRawParams.Designer.cs index 389ce857b85ca17cbcb74bd9c73354e77b529bea..6b072f30bfaff4416f034dcc9f7e7b69f60639f0 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRawParams.Designer.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRawParams.Designer.cs @@ -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; diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRawParams.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRawParams.cs index a131ea1b176dc97d0eb90c8033416532b542b548..a831f31c1b947711b63a566994c1901699ac0017 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRawParams.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRawParams.cs @@ -10,6 +10,7 @@ using System.Text; using System.Windows.Forms; using log4net; using ArdupilotMega.Controls.BackstageView; +using ArdupilotMega.Controls; namespace ArdupilotMega.GCSViews.ConfigurationView { diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRawParams.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRawParams.resx index 3a3f70f56576d95fdc68402cf8cfe3deb1f8e21a..e4bef97a511c08cab81cb316cf174b045261fd5c 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRawParams.resx +++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRawParams.resx @@ -142,7 +142,7 @@ <value>BUT_compare</value> </data> <data name=">>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=">>BUT_compare.Parent" xml:space="preserve"> <value>$this</value> @@ -172,7 +172,7 @@ <value>BUT_rerequestparams</value> </data> <data name=">>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=">>BUT_rerequestparams.Parent" xml:space="preserve"> <value>$this</value> @@ -202,7 +202,7 @@ <value>BUT_writePIDS</value> </data> <data name=">>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=">>BUT_writePIDS.Parent" xml:space="preserve"> <value>$this</value> @@ -235,7 +235,7 @@ <value>BUT_save</value> </data> <data name=">>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=">>BUT_save.Parent" xml:space="preserve"> <value>$this</value> @@ -268,7 +268,7 @@ <value>BUT_load</value> </data> <data name=">>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=">>BUT_load.Parent" xml:space="preserve"> <value>$this</value> diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigTradHeli.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigTradHeli.Designer.cs index 211699c119821a2f9f4c7b13feffdf1f7c09ed5b..7a4c66226423117a8bd97b571ac1a6dbf18d68a2 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigTradHeli.Designer.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigTradHeli.Designer.cs @@ -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; diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigTradHeli.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigTradHeli.cs index c4d3effe1d9b238b79f19754dbda457af4d2369f..6f99332ff1f3bd37ec7dab6d4667f9e3f92d7ac0 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigTradHeli.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigTradHeli.cs @@ -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); } diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigTradHeli.resx b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigTradHeli.resx index 133ab792d2369e92796645e02238adf9f45c00ad..56cc3b35a7a04102678621b11aac4a9085291b49 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigTradHeli.resx +++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigTradHeli.resx @@ -217,7 +217,7 @@ <value>BUT_swash_manual</value> </data> <data name=">>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=">>BUT_swash_manual.Parent" xml:space="preserve"> <value>$this</value> @@ -409,7 +409,7 @@ <value>BUT_HS4save</value> </data> <data name=">>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=">>BUT_HS4save.Parent" xml:space="preserve"> <value>$this</value> @@ -550,7 +550,7 @@ <value>BUT_0collective</value> </data> <data name=">>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=">>BUT_0collective.Parent" xml:space="preserve"> <value>groupBox1</value> diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/Configuration.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/Configuration.cs index 780efaf1c5c7c24b5b3085ae4126b02809e8a350..60cc50f7b972196fb95627c1100f937b78143559 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/Configuration.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/Configuration.cs @@ -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")); diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/Setup.cs b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/Setup.cs index fbd2dcbc8312fd682dc5c02966ddfddf2b4bd67a..9b13408161b19e9a611731745fa613333391b685 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/Setup.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/Setup.cs @@ -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")); diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/Firmware.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/Firmware.Designer.cs index fa56951ee98672e185197c7e5ab6421c128665b2..8dd5014360c78f32c35b3d3b1238b5d9f712bfbd 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/Firmware.Designer.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/Firmware.Designer.cs @@ -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(); diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/Firmware.cs b/Tools/ArdupilotMegaPlanner/GCSViews/Firmware.cs index 8971889c8b46a70669800e3c399041ce9925246b..cc696b67458aec0c943a52f81616c7146f11abe9 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/Firmware.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/Firmware.cs @@ -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"); diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/Firmware.resx b/Tools/ArdupilotMegaPlanner/GCSViews/Firmware.resx index 2f436fe289735ef3f1ead5b9554c57a6591c0796..be5eb92e015ff0e6025fd8b0cfd6afb181d3d2c9 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/Firmware.resx +++ b/Tools/ArdupilotMegaPlanner/GCSViews/Firmware.resx @@ -367,7 +367,7 @@ <value>BUT_setup</value> </data> <data name=">>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=">>BUT_setup.Parent" xml:space="preserve"> <value>$this</value> diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.Designer.cs index 9b17adaae6ec509450d5592361e9404bb3a49a43..87435b07aac85a2813363336a4c4802e172f89f3 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.Designer.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.Designer.cs @@ -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; } } \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.cs b/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.cs index 11e610087c4d6991d9bd0eb0f2d2a10c7d3e3b9f..da690be4532422a5dd34d00a441c482552bb8970 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.cs @@ -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) diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.resx b/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.resx index 2cbf5522e0f3730313d7b488687fbfd45a076aa7..8921faf5e3eae682cc3aabc2c405d38cd73367aa 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.resx +++ b/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.resx @@ -208,7 +208,7 @@ <value>hud1</value> </data> <data name=">>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=">>hud1.Parent" xml:space="preserve"> <value>SubMainLeft.Panel1</value> @@ -247,7 +247,7 @@ <value>BUT_script</value> </data> <data name=">>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=">>BUT_script.Parent" xml:space="preserve"> <value>tabActions</value> @@ -280,7 +280,7 @@ <value>BUT_joystick</value> </data> <data name=">>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=">>BUT_joystick.Parent" xml:space="preserve"> <value>tabActions</value> @@ -310,7 +310,7 @@ <value>BUT_quickmanual</value> </data> <data name=">>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=">>BUT_quickmanual.Parent" xml:space="preserve"> <value>tabActions</value> @@ -340,7 +340,7 @@ <value>BUT_quickrtl</value> </data> <data name=">>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=">>BUT_quickrtl.Parent" xml:space="preserve"> <value>tabActions</value> @@ -370,7 +370,7 @@ <value>BUT_quickauto</value> </data> <data name=">>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=">>BUT_quickauto.Parent" xml:space="preserve"> <value>tabActions</value> @@ -424,7 +424,7 @@ <value>BUT_setwp</value> </data> <data name=">>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=">>BUT_setwp.Parent" xml:space="preserve"> <value>tabActions</value> @@ -475,7 +475,7 @@ <value>BUT_setmode</value> </data> <data name=">>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=">>BUT_setmode.Parent" xml:space="preserve"> <value>tabActions</value> @@ -505,7 +505,7 @@ <value>BUT_clear_track</value> </data> <data name=">>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=">>BUT_clear_track.Parent" xml:space="preserve"> <value>tabActions</value> @@ -556,7 +556,7 @@ <value>BUT_Homealt</value> </data> <data name=">>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=">>BUT_Homealt.Parent" xml:space="preserve"> <value>tabActions</value> @@ -586,7 +586,7 @@ <value>BUT_RAWSensor</value> </data> <data name=">>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=">>BUT_RAWSensor.Parent" xml:space="preserve"> <value>tabActions</value> @@ -616,7 +616,7 @@ <value>BUTrestartmission</value> </data> <data name=">>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=">>BUTrestartmission.Parent" xml:space="preserve"> <value>tabActions</value> @@ -646,7 +646,7 @@ <value>BUTactiondo</value> </data> <data name=">>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=">>BUTactiondo.Parent" xml:space="preserve"> <value>tabActions</value> @@ -700,7 +700,7 @@ <value>Gvspeed</value> </data> <data name=">>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=">>Gvspeed.Parent" xml:space="preserve"> <value>tabGauges</value> @@ -730,7 +730,7 @@ <value>Gheading</value> </data> <data name=">>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=">>Gheading.Parent" xml:space="preserve"> <value>tabGauges</value> @@ -760,7 +760,7 @@ <value>Galt</value> </data> <data name=">>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=">>Galt.Parent" xml:space="preserve"> <value>tabGauges</value> @@ -793,7 +793,7 @@ <value>Gspeed</value> </data> <data name=">>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=">>Gspeed.Parent" xml:space="preserve"> <value>tabGauges</value> @@ -874,7 +874,7 @@ <value>lbl_logpercent</value> </data> <data name=">>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=">>lbl_logpercent.Parent" xml:space="preserve"> <value>tabTLogs</value> @@ -925,7 +925,7 @@ <value>BUT_log2kml</value> </data> <data name=">>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=">>BUT_log2kml.Parent" xml:space="preserve"> <value>tabTLogs</value> @@ -976,7 +976,7 @@ <value>BUT_playlog</value> </data> <data name=">>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=">>BUT_playlog.Parent" xml:space="preserve"> <value>tabTLogs</value> @@ -1003,7 +1003,7 @@ <value>BUT_loadtelem</value> </data> <data name=">>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=">>BUT_loadtelem.Parent" xml:space="preserve"> <value>tabTLogs</value> @@ -1192,7 +1192,7 @@ <value>lbl_hdop</value> </data> <data name=">>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=">>lbl_hdop.Parent" xml:space="preserve"> <value>splitContainer1.Panel2</value> @@ -1225,7 +1225,7 @@ <value>lbl_sats</value> </data> <data name=">>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=">>lbl_sats.Parent" xml:space="preserve"> <value>splitContainer1.Panel2</value> @@ -1255,7 +1255,7 @@ <value>lbl_winddir</value> </data> <data name=">>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=">>lbl_winddir.Parent" xml:space="preserve"> <value>splitContainer1.Panel2</value> @@ -1285,7 +1285,7 @@ <value>lbl_windvel</value> </data> <data name=">>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=">>lbl_windvel.Parent" xml:space="preserve"> <value>splitContainer1.Panel2</value> @@ -1457,7 +1457,7 @@ <value>gMapControl1</value> </data> <data name=">>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=">>gMapControl1.Parent" xml:space="preserve"> <value>splitContainer1.Panel2</value> @@ -1520,7 +1520,7 @@ <value>TXT_lat</value> </data> <data name=">>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=">>TXT_lat.Parent" xml:space="preserve"> <value>panel1</value> @@ -1577,7 +1577,7 @@ <value>label1</value> </data> <data name=">>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=">>label1.Parent" xml:space="preserve"> <value>panel1</value> @@ -1607,7 +1607,7 @@ <value>TXT_long</value> </data> <data name=">>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=">>TXT_long.Parent" xml:space="preserve"> <value>panel1</value> @@ -1637,7 +1637,7 @@ <value>TXT_alt</value> </data> <data name=">>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=">>TXT_alt.Parent" xml:space="preserve"> <value>panel1</value> @@ -1838,7 +1838,7 @@ <value>label6</value> </data> <data name=">>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=">>label6.Parent" xml:space="preserve"> <value>$this</value> @@ -1916,6 +1916,6 @@ <value>FlightData</value> </data> <data name=">>$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> \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.Designer.cs index acadb4b9052d417737587494664877264ac01c73..524e96127bb35d28763aa168af1ac91067ef964b 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.Designer.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.Designer.cs @@ -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; diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.cs b/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.cs index 5e386318598f7ac3e4e77ca65233ae2d8f210d68..bdf89907b3dcae1e96f3044748d2fe93dcc64131 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.cs @@ -21,6 +21,7 @@ using System.Threading; using log4net; using SharpKml.Base; using SharpKml.Dom; +using ArdupilotMega.Controls; diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.resx b/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.resx index 8db443f0a28c67a8c1ce9187e4669499217ed5c7..f70e995eaddab880f0ad88ef082b3f5fbf15fcfc 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.resx +++ b/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.resx @@ -556,7 +556,7 @@ <value>BUT_write</value> </data> <data name=">>BUT_write.Type" xml:space="preserve"> - <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value> + <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value> </data> <data name=">>BUT_write.Parent" xml:space="preserve"> <value>panel5</value> @@ -583,7 +583,7 @@ <value>BUT_read</value> </data> <data name=">>BUT_read.Type" xml:space="preserve"> - <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value> + <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value> </data> <data name=">>BUT_read.Parent" xml:space="preserve"> <value>panel5</value> @@ -610,7 +610,7 @@ <value>SaveFile</value> </data> <data name=">>SaveFile.Type" xml:space="preserve"> - <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value> + <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value> </data> <data name=">>SaveFile.Parent" xml:space="preserve"> <value>panel5</value> @@ -637,7 +637,7 @@ <value>BUT_loadwpfile</value> </data> <data name=">>BUT_loadwpfile.Type" xml:space="preserve"> - <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value> + <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value> </data> <data name=">>BUT_loadwpfile.Parent" xml:space="preserve"> <value>panel5</value> @@ -1261,7 +1261,7 @@ <value>BUT_loadkml</value> </data> <data name=">>BUT_loadkml.Type" xml:space="preserve"> - <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value> + <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value> </data> <data name=">>BUT_loadkml.Parent" xml:space="preserve"> <value>panelWaypoints</value> @@ -1291,7 +1291,7 @@ <value>BUT_zoomto</value> </data> <data name=">>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=">>BUT_zoomto.Parent" xml:space="preserve"> <value>panelWaypoints</value> @@ -1321,7 +1321,7 @@ <value>BUT_Camera</value> </data> <data name=">>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=">>BUT_Camera.Parent" xml:space="preserve"> <value>panelWaypoints</value> @@ -1351,7 +1351,7 @@ <value>BUT_grid</value> </data> <data name=">>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=">>BUT_grid.Parent" xml:space="preserve"> <value>panelWaypoints</value> @@ -1381,7 +1381,7 @@ <value>BUT_Prefetch</value> </data> <data name=">>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=">>BUT_Prefetch.Parent" xml:space="preserve"> <value>panelWaypoints</value> @@ -1411,7 +1411,7 @@ <value>button1</value> </data> <data name=">>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=">>button1.Parent" xml:space="preserve"> <value>panelWaypoints</value> @@ -1441,7 +1441,7 @@ <value>BUT_Add</value> </data> <data name=">>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=">>BUT_Add.Parent" xml:space="preserve"> <value>panelWaypoints</value> diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/Help.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/Help.Designer.cs index 965140d1d58611637211d5ee19fc4e7f6a5d5f2c..9151f64fdb71a80d2920c1c97b7c1cbefe9fa593 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/Help.Designer.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/Help.Designer.cs @@ -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; } diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/Help.resx b/Tools/ArdupilotMegaPlanner/GCSViews/Help.resx index 8d7938a05c62d20e156439e1e1402b91b2a7a014..f5e2d6cd4256627cf31be16f711c12dec7ddfcf0 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/Help.resx +++ b/Tools/ArdupilotMegaPlanner/GCSViews/Help.resx @@ -196,7 +196,7 @@ <value>BUT_updatecheck</value> </data> <data name=">>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=">>BUT_updatecheck.Parent" xml:space="preserve"> <value>$this</value> diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/Simulation.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/Simulation.Designer.cs index 45318952a8076a73586a2e99cb6facd35ca9ba12..54ae0bb1a203d0891274a5e7e2f9b552952654dc 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/Simulation.Designer.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/Simulation.Designer.cs @@ -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; diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/Simulation.cs b/Tools/ArdupilotMegaPlanner/GCSViews/Simulation.cs index fca5683952e14d4a172b4163f00cd3792b5e3206..307090fb1b3a3ef47635cb62f055a8cd5802eaa2 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/Simulation.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/Simulation.cs @@ -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 diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/Simulation.resx b/Tools/ArdupilotMegaPlanner/GCSViews/Simulation.resx index b78bdb87cf109523e6c271c50a6ee78681c58f53..0b480ae370df648dee9c1d7f8a481dc42c7add69 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/Simulation.resx +++ b/Tools/ArdupilotMegaPlanner/GCSViews/Simulation.resx @@ -261,7 +261,7 @@ <value>ConnectComPort</value> </data> <data name=">>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=">>ConnectComPort.Parent" xml:space="preserve"> <value>panel5</value> @@ -309,7 +309,7 @@ <value>TXT_roll</value> </data> <data name=">>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=">>TXT_roll.Parent" xml:space="preserve"> <value>panel2</value> @@ -330,7 +330,7 @@ <value>TXT_pitch</value> </data> <data name=">>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=">>TXT_pitch.Parent" xml:space="preserve"> <value>panel2</value> @@ -351,7 +351,7 @@ <value>TXT_heading</value> </data> <data name=">>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=">>TXT_heading.Parent" xml:space="preserve"> <value>panel2</value> @@ -372,7 +372,7 @@ <value>TXT_wpdist</value> </data> <data name=">>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=">>TXT_wpdist.Parent" xml:space="preserve"> <value>panel4</value> @@ -396,7 +396,7 @@ <value>TXT_bererror</value> </data> <data name=">>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=">>TXT_bererror.Parent" xml:space="preserve"> <value>panel4</value> @@ -417,7 +417,7 @@ <value>TXT_alterror</value> </data> <data name=">>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=">>TXT_alterror.Parent" xml:space="preserve"> <value>panel4</value> @@ -438,7 +438,7 @@ <value>TXT_lat</value> </data> <data name=">>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=">>TXT_lat.Parent" xml:space="preserve"> <value>panel1</value> @@ -459,7 +459,7 @@ <value>TXT_long</value> </data> <data name=">>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=">>TXT_long.Parent" xml:space="preserve"> <value>panel1</value> @@ -480,7 +480,7 @@ <value>TXT_alt</value> </data> <data name=">>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=">>TXT_alt.Parent" xml:space="preserve"> <value>panel1</value> @@ -504,7 +504,7 @@ <value>SaveSettings</value> </data> <data name=">>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=">>SaveSettings.Parent" xml:space="preserve"> <value>$this</value> @@ -588,7 +588,7 @@ <value>TXT_servoroll</value> </data> <data name=">>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=">>TXT_servoroll.Parent" xml:space="preserve"> <value>panel3</value> @@ -609,7 +609,7 @@ <value>TXT_servopitch</value> </data> <data name=">>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=">>TXT_servopitch.Parent" xml:space="preserve"> <value>panel3</value> @@ -630,7 +630,7 @@ <value>TXT_servorudder</value> </data> <data name=">>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=">>TXT_servorudder.Parent" xml:space="preserve"> <value>panel3</value> @@ -651,7 +651,7 @@ <value>TXT_servothrottle</value> </data> <data name=">>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=">>TXT_servothrottle.Parent" xml:space="preserve"> <value>panel3</value> @@ -675,7 +675,7 @@ <value>label4</value> </data> <data name=">>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=">>label4.Parent" xml:space="preserve"> <value>panel1</value> @@ -699,7 +699,7 @@ <value>label3</value> </data> <data name=">>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=">>label3.Parent" xml:space="preserve"> <value>panel1</value> @@ -723,7 +723,7 @@ <value>label2</value> </data> <data name=">>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=">>label2.Parent" xml:space="preserve"> <value>panel1</value> @@ -747,7 +747,7 @@ <value>label1</value> </data> <data name=">>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=">>label1.Parent" xml:space="preserve"> <value>panel1</value> @@ -792,7 +792,7 @@ <value>label30</value> </data> <data name=">>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=">>label30.Parent" xml:space="preserve"> <value>panel2</value> @@ -813,7 +813,7 @@ <value>TXT_yaw</value> </data> <data name=">>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=">>TXT_yaw.Parent" xml:space="preserve"> <value>panel2</value> @@ -837,7 +837,7 @@ <value>label11</value> </data> <data name=">>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=">>label11.Parent" xml:space="preserve"> <value>panel2</value> @@ -861,7 +861,7 @@ <value>label7</value> </data> <data name=">>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=">>label7.Parent" xml:space="preserve"> <value>panel2</value> @@ -885,7 +885,7 @@ <value>label6</value> </data> <data name=">>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=">>label6.Parent" xml:space="preserve"> <value>panel2</value> @@ -909,7 +909,7 @@ <value>label5</value> </data> <data name=">>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=">>label5.Parent" xml:space="preserve"> <value>panel2</value> @@ -954,7 +954,7 @@ <value>label8</value> </data> <data name=">>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=">>label8.Parent" xml:space="preserve"> <value>panel4</value> @@ -978,7 +978,7 @@ <value>label9</value> </data> <data name=">>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=">>label9.Parent" xml:space="preserve"> <value>panel4</value> @@ -1002,7 +1002,7 @@ <value>label10</value> </data> <data name=">>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=">>label10.Parent" xml:space="preserve"> <value>panel4</value> @@ -1026,7 +1026,7 @@ <value>label16</value> </data> <data name=">>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=">>label16.Parent" xml:space="preserve"> <value>panel3</value> @@ -1050,7 +1050,7 @@ <value>label15</value> </data> <data name=">>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=">>label15.Parent" xml:space="preserve"> <value>panel3</value> @@ -1074,7 +1074,7 @@ <value>label14</value> </data> <data name=">>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=">>label14.Parent" xml:space="preserve"> <value>panel3</value> @@ -1098,7 +1098,7 @@ <value>label13</value> </data> <data name=">>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=">>label13.Parent" xml:space="preserve"> <value>panel3</value> @@ -1122,7 +1122,7 @@ <value>label12</value> </data> <data name=">>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=">>label12.Parent" xml:space="preserve"> <value>panel3</value> @@ -1167,7 +1167,7 @@ <value>label20</value> </data> <data name=">>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=">>label20.Parent" xml:space="preserve"> <value>panel4</value> @@ -1191,7 +1191,7 @@ <value>label19</value> </data> <data name=">>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=">>label19.Parent" xml:space="preserve"> <value>panel4</value> @@ -1212,7 +1212,7 @@ <value>TXT_control_mode</value> </data> <data name=">>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=">>TXT_control_mode.Parent" xml:space="preserve"> <value>panel4</value> @@ -1233,7 +1233,7 @@ <value>TXT_WP</value> </data> <data name=">>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=">>TXT_WP.Parent" xml:space="preserve"> <value>panel4</value> @@ -1257,7 +1257,7 @@ <value>label18</value> </data> <data name=">>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=">>label18.Parent" xml:space="preserve"> <value>panel4</value> @@ -1302,7 +1302,7 @@ <value>label17</value> </data> <data name=">>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=">>label17.Parent" xml:space="preserve"> <value>$this</value> @@ -1375,7 +1375,7 @@ <value>label28</value> </data> <data name=">>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=">>label28.Parent" xml:space="preserve"> <value>panel6</value> @@ -1399,7 +1399,7 @@ <value>label29</value> </data> <data name=">>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=">>label29.Parent" xml:space="preserve"> <value>panel6</value> @@ -1423,7 +1423,7 @@ <value>label27</value> </data> <data name=">>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=">>label27.Parent" xml:space="preserve"> <value>panel6</value> @@ -1447,7 +1447,7 @@ <value>label25</value> </data> <data name=">>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=">>label25.Parent" xml:space="preserve"> <value>panel6</value> @@ -1495,7 +1495,7 @@ <value>label24</value> </data> <data name=">>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=">>label24.Parent" xml:space="preserve"> <value>panel6</value> @@ -1519,7 +1519,7 @@ <value>label23</value> </data> <data name=">>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=">>label23.Parent" xml:space="preserve"> <value>panel6</value> @@ -1543,7 +1543,7 @@ <value>label22</value> </data> <data name=">>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=">>label22.Parent" xml:space="preserve"> <value>panel6</value> @@ -1567,7 +1567,7 @@ <value>label21</value> </data> <data name=">>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=">>label21.Parent" xml:space="preserve"> <value>panel6</value> @@ -1684,7 +1684,7 @@ <value>label26</value> </data> <data name=">>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=">>label26.Parent" xml:space="preserve"> <value>$this</value> @@ -1855,7 +1855,7 @@ <value>but_advsettings</value> </data> <data name=">>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=">>but_advsettings.Parent" xml:space="preserve"> <value>$this</value> @@ -1939,7 +1939,7 @@ <value>BUT_startfgquad</value> </data> <data name=">>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=">>BUT_startfgquad.Parent" xml:space="preserve"> <value>$this</value> @@ -1966,7 +1966,7 @@ <value>BUT_startfgplane</value> </data> <data name=">>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=">>BUT_startfgplane.Parent" xml:space="preserve"> <value>$this</value> @@ -1993,7 +1993,7 @@ <value>BUT_startxplane</value> </data> <data name=">>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=">>BUT_startxplane.Parent" xml:space="preserve"> <value>$this</value> diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/Terminal.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/Terminal.Designer.cs index 29b1c3207ef8503143870c65331209f50f0b00e5..eacae4685d4fac8388653a215d588cebc9f9ef36 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/Terminal.Designer.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/Terminal.Designer.cs @@ -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; } } diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/Terminal.cs b/Tools/ArdupilotMegaPlanner/GCSViews/Terminal.cs index 2c4897acef1f302b3ca9fa412ac70cf4f3f610d6..9dbeb0d323d219ea84d326288aaf922e60cb38ce 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/Terminal.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/Terminal.cs @@ -8,6 +8,8 @@ using System.Text; using System.Windows.Forms; using ArdupilotMega; using System.IO.Ports; +using ArdupilotMega.Comms; + namespace ArdupilotMega.GCSViews { diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/Terminal.resx b/Tools/ArdupilotMegaPlanner/GCSViews/Terminal.resx index 4da6d80a1b95ec8254242776dc932adb37a5fdb6..af41b2749b586c60d2d4874a29d8cadac5eeea1d 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/Terminal.resx +++ b/Tools/ArdupilotMegaPlanner/GCSViews/Terminal.resx @@ -166,7 +166,7 @@ <value>BUTsetupshow</value> </data> <data name=">>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=">>BUTsetupshow.Parent" xml:space="preserve"> <value>$this</value> @@ -190,7 +190,7 @@ <value>BUTradiosetup</value> </data> <data name=">>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=">>BUTradiosetup.Parent" xml:space="preserve"> <value>$this</value> @@ -214,7 +214,7 @@ <value>BUTtests</value> </data> <data name=">>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=">>BUTtests.Parent" xml:space="preserve"> <value>$this</value> @@ -238,7 +238,7 @@ <value>Logs</value> </data> <data name=">>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=">>Logs.Parent" xml:space="preserve"> <value>$this</value> @@ -262,7 +262,7 @@ <value>BUT_logbrowse</value> </data> <data name=">>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=">>BUT_logbrowse.Parent" xml:space="preserve"> <value>$this</value> diff --git a/Tools/ArdupilotMegaPlanner/JoystickSetup.Designer.cs b/Tools/ArdupilotMegaPlanner/JoystickSetup.Designer.cs index 567ecfd7c92f6aad26c9f5d8db3835ca4c121b6a..6b6ab46c6d1fd6c95dcb780a73c9823d3b8439ff 100644 --- a/Tools/ArdupilotMegaPlanner/JoystickSetup.Designer.cs +++ b/Tools/ArdupilotMegaPlanner/JoystickSetup.Designer.cs @@ -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; diff --git a/Tools/ArdupilotMegaPlanner/JoystickSetup.cs b/Tools/ArdupilotMegaPlanner/JoystickSetup.cs index 92e7c613d49f4a727bbd24f67c813dd715965415..c750515d5c5c5cf670799f2a1851ea02acf31a3f 100644 --- a/Tools/ArdupilotMegaPlanner/JoystickSetup.cs +++ b/Tools/ArdupilotMegaPlanner/JoystickSetup.cs @@ -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) diff --git a/Tools/ArdupilotMegaPlanner/JoystickSetup.resx b/Tools/ArdupilotMegaPlanner/JoystickSetup.resx index 9b38147048441121b14782ec38cc3762f08c8e56..1912c313d486c68ec03935bef7acf3e6524333e7 100644 --- a/Tools/ArdupilotMegaPlanner/JoystickSetup.resx +++ b/Tools/ArdupilotMegaPlanner/JoystickSetup.resx @@ -1258,7 +1258,7 @@ <value>BUT_detch8</value> </data> <data name=">>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=">>BUT_detch8.Parent" xml:space="preserve"> <value>$this</value> @@ -1309,7 +1309,7 @@ <value>BUT_detch4</value> </data> <data name=">>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=">>BUT_detch4.Parent" xml:space="preserve"> <value>$this</value> @@ -1336,7 +1336,7 @@ <value>BUT_detch3</value> </data> <data name=">>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=">>BUT_detch3.Parent" xml:space="preserve"> <value>$this</value> @@ -1363,7 +1363,7 @@ <value>BUT_detch2</value> </data> <data name=">>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=">>BUT_detch2.Parent" xml:space="preserve"> <value>$this</value> @@ -1390,7 +1390,7 @@ <value>BUT_detch1</value> </data> <data name=">>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=">>BUT_detch1.Parent" xml:space="preserve"> <value>$this</value> @@ -1417,7 +1417,7 @@ <value>BUT_enable</value> </data> <data name=">>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=">>BUT_enable.Parent" xml:space="preserve"> <value>$this</value> @@ -1444,7 +1444,7 @@ <value>BUT_save</value> </data> <data name=">>BUT_save.Type" xml:space="preserve"> - <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value> + <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value> </data> <data name=">>BUT_save.Parent" xml:space="preserve"> <value>$this</value> @@ -1567,7 +1567,7 @@ <value>BUT_detch5</value> </data> <data name=">>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=">>BUT_detch5.Parent" xml:space="preserve"> <value>$this</value> @@ -1618,7 +1618,7 @@ <value>BUT_detch6</value> </data> <data name=">>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=">>BUT_detch6.Parent" xml:space="preserve"> <value>$this</value> @@ -1669,7 +1669,7 @@ <value>BUT_detch7</value> </data> <data name=">>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=">>BUT_detch7.Parent" xml:space="preserve"> <value>$this</value> diff --git a/Tools/ArdupilotMegaPlanner/Log.Designer.cs b/Tools/ArdupilotMegaPlanner/Log.Designer.cs index 97aeebba07bff47fde6f8bfa480182665929e9e8..5268c07d9e4f175b7b60dceeceaca94ac20b11d9 100644 --- a/Tools/ArdupilotMegaPlanner/Log.Designer.cs +++ b/Tools/ArdupilotMegaPlanner/Log.Designer.cs @@ -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; } } \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/Log.cs b/Tools/ArdupilotMegaPlanner/Log.cs index 5bef471ab66af891c2b3195dd2473da43ca2d629..520c59ac4425a4a8371ef0d8fe1c87a3ac307718 100644 --- a/Tools/ArdupilotMegaPlanner/Log.cs +++ b/Tools/ArdupilotMegaPlanner/Log.cs @@ -17,6 +17,7 @@ using ICSharpCode.SharpZipLib.Zip; using ICSharpCode.SharpZipLib.Checksums; using ICSharpCode.SharpZipLib.Core; using log4net; +using ArdupilotMega.Comms; namespace ArdupilotMega diff --git a/Tools/ArdupilotMegaPlanner/Log.resx b/Tools/ArdupilotMegaPlanner/Log.resx index b1e09b2bb41769c75905bbf38eb1b9771878e7d8..cf6b035012933b6bcba080dc2579a42da1b25251 100644 --- a/Tools/ArdupilotMegaPlanner/Log.resx +++ b/Tools/ArdupilotMegaPlanner/Log.resx @@ -159,7 +159,7 @@ <value>BUT_DLall</value> </data> <data name=">>BUT_DLall.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=">>BUT_DLall.Parent" xml:space="preserve"> <value>$this</value> @@ -183,7 +183,7 @@ <value>BUT_DLthese</value> </data> <data name=">>BUT_DLthese.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=">>BUT_DLthese.Parent" xml:space="preserve"> <value>$this</value> @@ -207,7 +207,7 @@ <value>BUT_clearlogs</value> </data> <data name=">>BUT_clearlogs.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=">>BUT_clearlogs.Parent" xml:space="preserve"> <value>$this</value> @@ -276,7 +276,7 @@ <value>BUT_redokml</value> </data> <data name=">>BUT_redokml.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=">>BUT_redokml.Parent" xml:space="preserve"> <value>$this</value> @@ -300,7 +300,7 @@ <value>BUT_firstperson</value> </data> <data name=">>BUT_firstperson.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=">>BUT_firstperson.Parent" xml:space="preserve"> <value>$this</value> diff --git a/Tools/ArdupilotMegaPlanner/LogBrowse.designer.cs b/Tools/ArdupilotMegaPlanner/LogBrowse.designer.cs index e262c3dc0ec247817c13725e6d9fdbeb1a9ebf0a..aa1db0eff6048619701dd24ed144190e45cd1919 100644 --- a/Tools/ArdupilotMegaPlanner/LogBrowse.designer.cs +++ b/Tools/ArdupilotMegaPlanner/LogBrowse.designer.cs @@ -32,9 +32,9 @@ System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(LogBrowse)); this.dataGridView1 = new System.Windows.Forms.DataGridView(); this.zg1 = new ZedGraph.ZedGraphControl(); - this.Graphit = new ArdupilotMega.MyButton(); - this.BUT_cleargraph = new ArdupilotMega.MyButton(); - this.BUT_loadlog = new ArdupilotMega.MyButton(); + this.Graphit = new ArdupilotMega.Controls.MyButton(); + this.BUT_cleargraph = new ArdupilotMega.Controls.MyButton(); + this.BUT_loadlog = new ArdupilotMega.Controls.MyButton(); this.toolTip1 = new System.Windows.Forms.ToolTip(this.components); ((System.ComponentModel.ISupportInitialize)(this.dataGridView1)).BeginInit(); this.SuspendLayout(); @@ -107,9 +107,9 @@ private System.Windows.Forms.DataGridView dataGridView1; private ZedGraph.ZedGraphControl zg1; - private MyButton Graphit; - private MyButton BUT_cleargraph; - private MyButton BUT_loadlog; + private ArdupilotMega.Controls.MyButton Graphit; + private ArdupilotMega.Controls.MyButton BUT_cleargraph; + private ArdupilotMega.Controls.MyButton BUT_loadlog; private System.Windows.Forms.ToolTip toolTip1; } } diff --git a/Tools/ArdupilotMegaPlanner/LogBrowse.resx b/Tools/ArdupilotMegaPlanner/LogBrowse.resx index f122be17d458741355e2f55497bbc04dd90257dc..93a5287ca166f1d4812a8365d813600e782dc3f2 100644 --- a/Tools/ArdupilotMegaPlanner/LogBrowse.resx +++ b/Tools/ArdupilotMegaPlanner/LogBrowse.resx @@ -193,7 +193,7 @@ <value>Graphit</value> </data> <data name=">>Graphit.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=">>Graphit.Parent" xml:space="preserve"> <value>$this</value> @@ -220,7 +220,7 @@ <value>BUT_cleargraph</value> </data> <data name=">>BUT_cleargraph.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=">>BUT_cleargraph.Parent" xml:space="preserve"> <value>$this</value> @@ -247,7 +247,7 @@ <value>BUT_loadlog</value> </data> <data name=">>BUT_loadlog.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=">>BUT_loadlog.Parent" xml:space="preserve"> <value>$this</value> diff --git a/Tools/ArdupilotMegaPlanner/MAVLink.cs b/Tools/ArdupilotMegaPlanner/MAVLink.cs index b9fa51deecafffcaeb97154d8c17e7b4dcd8d9be..485ef2a42afc9ea0332ae8a6a4f8d778e09df7eb 100644 --- a/Tools/ArdupilotMegaPlanner/MAVLink.cs +++ b/Tools/ArdupilotMegaPlanner/MAVLink.cs @@ -1,7 +1,6 @@ using System; using System.Collections.Generic; using System.Text; -using System.IO.Ports; using System.Runtime.InteropServices; using System.Collections; // hashs using System.Diagnostics; // stopwatch @@ -13,6 +12,7 @@ using System.Threading; using ArdupilotMega.Controls; using System.ComponentModel; using log4net; +using ArdupilotMega.Comms; namespace ArdupilotMega { @@ -1027,9 +1027,9 @@ namespace ArdupilotMega public void requestDatastream(byte id, byte hzrate) { - - double pps = 0; /* + double pps = 0; + switch (id) { case (byte)MAVLink.MAV_DATA_STREAM.ALL: @@ -1962,7 +1962,7 @@ namespace ArdupilotMega // test fabs idea - http://diydrones.com/profiles/blogs/flying-with-joystick?commentId=705844%3AComment%3A818712&xg_source=msg_com_blogpost if (BaseStream.IsOpen && BaseStream.BytesToWrite > 0) { - // slow down execution. + // slow down execution. else 100% cpu Thread.Sleep(1); return new byte[0]; } @@ -2161,8 +2161,18 @@ namespace ArdupilotMega { log.InfoFormat("Mavlink Bad Packet (Len Fail) len {0} pkno {1}", temp.Length, temp[5]); #if MAVLINK10 - if (temp.Length == 11 && temp[0] == 'U' && temp[5] == 0) - throw new Exception("Mavlink 0.9 Heartbeat, Please upgrade your AP, This planner is for Mavlink 1.0\n\n"); + if (temp.Length == 11 && temp[0] == 'U' && temp[5] == 0){ + string message ="Mavlink 0.9 Heartbeat, Please upgrade your AP, This planner is for Mavlink 1.0\n\n"; + System.Windows.Forms.CustomMessageBox.Show(message); + throw new Exception(message); + } +#else + if (temp.Length == 17 && temp[0] == 254 && temp[5] == 0) + { + string message = "Mavlink 1.0 Heartbeat, Please Upgrade your Mission Planner, This planner is for Mavlink 0.9\n\n"; + System.Windows.Forms.CustomMessageBox.Show(message); + throw new Exception(message); + } #endif return new byte[0]; } diff --git a/Tools/ArdupilotMegaPlanner/MainV2.cs b/Tools/ArdupilotMegaPlanner/MainV2.cs index bc811c7c382eeade651835d1a6eed3597f24f0e3..9a8e4d803eed80c8f87a6f06adbc8b38f61787dc 100644 --- a/Tools/ArdupilotMegaPlanner/MainV2.cs +++ b/Tools/ArdupilotMegaPlanner/MainV2.cs @@ -7,7 +7,6 @@ using System.Drawing; using System.Linq; using System.Text; using System.Windows.Forms; -using System.IO.Ports; using System.IO; using System.Xml; using System.Collections; @@ -25,6 +24,9 @@ using IronPython.Hosting; using log4net; using ArdupilotMega.Controls; using System.Security.Cryptography; +using ArdupilotMega.Comms; +using ArdupilotMega.Arduino; +using System.IO.Ports; namespace ArdupilotMega { @@ -198,7 +200,7 @@ namespace ArdupilotMega // CMB_serialport.SelectedIndex = 0; // } // ** new - _connectionControl.CMB_serialport.Items.AddRange(SerialPort.GetPortNames()); + _connectionControl.CMB_serialport.Items.AddRange(ArdupilotMega.Comms.SerialPort.GetPortNames()); _connectionControl.CMB_serialport.Items.Add("TCP"); _connectionControl.CMB_serialport.Items.Add("UDP"); if (_connectionControl.CMB_serialport.Items.Count > 0) @@ -357,7 +359,7 @@ namespace ArdupilotMega { string oldport = _connectionControl.CMB_serialport.Text; _connectionControl.CMB_serialport.Items.Clear(); - _connectionControl.CMB_serialport.Items.AddRange(SerialPort.GetPortNames()); + _connectionControl.CMB_serialport.Items.AddRange(ArdupilotMega.Comms.SerialPort.GetPortNames()); _connectionControl.CMB_serialport.Items.Add("TCP"); _connectionControl.CMB_serialport.Items.Add("UDP"); if (_connectionControl.CMB_serialport.Items.Contains(oldport)) @@ -566,7 +568,7 @@ namespace ArdupilotMega } else { - comPort.BaseStream = new SerialPort(); + comPort.BaseStream = new ArdupilotMega.Comms.SerialPort(); } try @@ -701,7 +703,7 @@ namespace ArdupilotMega else { _connectionControl.CMB_baudrate.Enabled = true; - MainV2.comPort.BaseStream = new ArdupilotMega.SerialPort(); + MainV2.comPort.BaseStream = new ArdupilotMega.Comms.SerialPort(); } try diff --git a/Tools/ArdupilotMegaPlanner/MavlinkLog.Designer.cs b/Tools/ArdupilotMegaPlanner/MavlinkLog.Designer.cs index cd4e7d8217cd2925c0d4eaec39e4eccbe9c120a8..0a77c3dfce3f8356cf7530d745530f7f5c5bc7b7 100644 --- a/Tools/ArdupilotMegaPlanner/MavlinkLog.Designer.cs +++ b/Tools/ArdupilotMegaPlanner/MavlinkLog.Designer.cs @@ -29,10 +29,10 @@ private void InitializeComponent() { System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(MavlinkLog)); - this.BUT_redokml = new ArdupilotMega.MyButton(); + this.BUT_redokml = new ArdupilotMega.Controls.MyButton(); this.progressBar1 = new System.Windows.Forms.ProgressBar(); - this.BUT_humanreadable = new ArdupilotMega.MyButton(); - this.BUT_graphmavlog = new ArdupilotMega.MyButton(); + this.BUT_humanreadable = new ArdupilotMega.Controls.MyButton(); + this.BUT_graphmavlog = new ArdupilotMega.Controls.MyButton(); this.zg1 = new ZedGraph.ZedGraphControl(); this.SuspendLayout(); // @@ -91,10 +91,10 @@ #endregion - private MyButton BUT_redokml; + private ArdupilotMega.Controls.MyButton BUT_redokml; private System.Windows.Forms.ProgressBar progressBar1; - private MyButton BUT_humanreadable; - private MyButton BUT_graphmavlog; + private ArdupilotMega.Controls.MyButton BUT_humanreadable; + private ArdupilotMega.Controls.MyButton BUT_graphmavlog; private ZedGraph.ZedGraphControl zg1; } } \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/MavlinkLog.resx b/Tools/ArdupilotMegaPlanner/MavlinkLog.resx index 9406a8df5f5c8e352a2b35f7e11b4af4a9380923..ec4f313eb2a2ab97a40ae6a344603890235fe1f4 100644 --- a/Tools/ArdupilotMegaPlanner/MavlinkLog.resx +++ b/Tools/ArdupilotMegaPlanner/MavlinkLog.resx @@ -139,7 +139,7 @@ <value>BUT_redokml</value> </data> <data name=">>BUT_redokml.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=">>BUT_redokml.Parent" xml:space="preserve"> <value>$this</value> @@ -193,7 +193,7 @@ <value>BUT_humanreadable</value> </data> <data name=">>BUT_humanreadable.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=">>BUT_humanreadable.Parent" xml:space="preserve"> <value>$this</value> @@ -223,7 +223,7 @@ <value>BUT_graphmavlog</value> </data> <data name=">>BUT_graphmavlog.Type" xml:space="preserve"> - <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value> + <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value> </data> <data name=">>BUT_graphmavlog.Parent" xml:space="preserve"> <value>$this</value> diff --git a/Tools/ArdupilotMegaPlanner/Msi/wix.pdb b/Tools/ArdupilotMegaPlanner/Msi/wix.pdb index 2d3c43918b28a85dab27db8f74975b70e7568756..a80ac1fd2da69224d03866940c09c8d5d87c5271 100644 Binary files a/Tools/ArdupilotMegaPlanner/Msi/wix.pdb and b/Tools/ArdupilotMegaPlanner/Msi/wix.pdb differ diff --git a/Tools/ArdupilotMegaPlanner/Properties/AssemblyInfo.cs b/Tools/ArdupilotMegaPlanner/Properties/AssemblyInfo.cs index f7879443a53a50a0cea171cfa286bb6acc7d8565..9df71d799de5fefeaa52eae24e42a2be073206c9 100644 --- a/Tools/ArdupilotMegaPlanner/Properties/AssemblyInfo.cs +++ b/Tools/ArdupilotMegaPlanner/Properties/AssemblyInfo.cs @@ -34,5 +34,5 @@ using System.Resources; // by using the '*' as shown below: // [assembly: AssemblyVersion("1.0.*")] [assembly: AssemblyVersion("1.1.*")] -[assembly: AssemblyFileVersion("1.1.74")] +[assembly: AssemblyFileVersion("1.1.75")] [assembly: NeutralResourcesLanguageAttribute("")] diff --git a/Tools/ArdupilotMegaPlanner/RAW_Sensor.Designer.cs b/Tools/ArdupilotMegaPlanner/RAW_Sensor.Designer.cs index 33fc751bc742c2817a2fa5d5d51a95659a77911b..15d24263fa2b0a8b5786b711730908d582ad266e 100644 --- a/Tools/ArdupilotMegaPlanner/RAW_Sensor.Designer.cs +++ b/Tools/ArdupilotMegaPlanner/RAW_Sensor.Designer.cs @@ -53,7 +53,7 @@ this.horizontalProgressBar2 = new ArdupilotMega.HorizontalProgressBar(); this.horizontalProgressBar1 = new ArdupilotMega.HorizontalProgressBar(); this.tabRawSensor = new System.Windows.Forms.TabPage(); - this.BUT_savecsv = new ArdupilotMega.MyButton(); + this.BUT_savecsv = new ArdupilotMega.Controls.MyButton(); this.label3 = new System.Windows.Forms.Label(); this.CMB_rawupdaterate = new System.Windows.Forms.ComboBox(); this.aGauge1 = new AGaugeApp.AGauge(); @@ -1129,7 +1129,7 @@ private VerticalProgressBar verticalProgressBar2; private VerticalProgressBar verticalProgressBar1; private System.Windows.Forms.TabControl tabControl; - private MyButton BUT_savecsv; + private ArdupilotMega.Controls.MyButton BUT_savecsv; } } \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/RAW_Sensor.resx b/Tools/ArdupilotMegaPlanner/RAW_Sensor.resx index e16890666dcc5f273550227be877e6ff38e3fb87..44efc71179e1b5dbf4818f13c527fb0c5e0af4e5 100644 --- a/Tools/ArdupilotMegaPlanner/RAW_Sensor.resx +++ b/Tools/ArdupilotMegaPlanner/RAW_Sensor.resx @@ -558,7 +558,7 @@ <value>BUT_savecsv</value> </data> <data name=">>BUT_savecsv.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=">>BUT_savecsv.Parent" xml:space="preserve"> <value>tabRawSensor</value> diff --git a/Tools/ArdupilotMegaPlanner/Radio/3DRradio.Designer.cs b/Tools/ArdupilotMegaPlanner/Radio/3DRradio.Designer.cs index aa2773fdfc016b0697efbfb05e73af90178e5587..ba32270f0c54a29767b7d8a7f4ab324af8165ea1 100644 --- a/Tools/ArdupilotMegaPlanner/Radio/3DRradio.Designer.cs +++ b/Tools/ArdupilotMegaPlanner/Radio/3DRradio.Designer.cs @@ -73,13 +73,13 @@ this.ATI = new System.Windows.Forms.TextBox(); this.label11 = new System.Windows.Forms.Label(); this.label12 = new System.Windows.Forms.Label(); - this.BUT_savesettings = new ArdupilotMega.MyButton(); - this.BUT_getcurrent = new ArdupilotMega.MyButton(); + this.BUT_savesettings = new ArdupilotMega.Controls.MyButton(); + this.BUT_getcurrent = new ArdupilotMega.Controls.MyButton(); this.lbl_status = new System.Windows.Forms.Label(); - this.BUT_upload = new ArdupilotMega.MyButton(); - this.BUT_syncS2 = new ArdupilotMega.MyButton(); - this.BUT_syncS3 = new ArdupilotMega.MyButton(); - this.BUT_syncS5 = new ArdupilotMega.MyButton(); + this.BUT_upload = new ArdupilotMega.Controls.MyButton(); + this.BUT_syncS2 = new ArdupilotMega.Controls.MyButton(); + this.BUT_syncS3 = new ArdupilotMega.Controls.MyButton(); + this.BUT_syncS5 = new ArdupilotMega.Controls.MyButton(); this.label13 = new System.Windows.Forms.Label(); this.label14 = new System.Windows.Forms.Label(); this.label15 = new System.Windows.Forms.Label(); @@ -98,9 +98,9 @@ this.label30 = new System.Windows.Forms.Label(); this.label31 = new System.Windows.Forms.Label(); this.label32 = new System.Windows.Forms.Label(); - this.BUT_syncS8 = new ArdupilotMega.MyButton(); - this.BUT_syncS9 = new ArdupilotMega.MyButton(); - this.BUT_syncS10 = new ArdupilotMega.MyButton(); + this.BUT_syncS8 = new ArdupilotMega.Controls.MyButton(); + this.BUT_syncS9 = new ArdupilotMega.Controls.MyButton(); + this.BUT_syncS10 = new ArdupilotMega.Controls.MyButton(); this.SuspendLayout(); // // Progressbar @@ -858,12 +858,12 @@ #endregion - private MyButton BUT_upload; + private ArdupilotMega.Controls.MyButton BUT_upload; private System.Windows.Forms.ProgressBar Progressbar; private System.Windows.Forms.Label lbl_status; private System.Windows.Forms.ComboBox S1; private System.Windows.Forms.Label label1; - private MyButton BUT_getcurrent; + private ArdupilotMega.Controls.MyButton BUT_getcurrent; private System.Windows.Forms.TextBox S0; private System.Windows.Forms.Label label2; private System.Windows.Forms.Label label3; @@ -878,7 +878,7 @@ private System.Windows.Forms.CheckBox S6; private System.Windows.Forms.Label label8; private System.Windows.Forms.CheckBox S7; - private MyButton BUT_savesettings; + private ArdupilotMega.Controls.MyButton BUT_savesettings; private System.Windows.Forms.ToolTip toolTip1; private System.Windows.Forms.CheckBox RS7; private System.Windows.Forms.CheckBox RS6; @@ -895,9 +895,9 @@ private System.Windows.Forms.TextBox RSSI; private System.Windows.Forms.Label label11; private System.Windows.Forms.Label label12; - private MyButton BUT_syncS2; - private MyButton BUT_syncS3; - private MyButton BUT_syncS5; + private ArdupilotMega.Controls.MyButton BUT_syncS2; + private ArdupilotMega.Controls.MyButton BUT_syncS3; + private ArdupilotMega.Controls.MyButton BUT_syncS5; private System.Windows.Forms.ComboBox S9; private System.Windows.Forms.ComboBox S10; private System.Windows.Forms.ComboBox S11; @@ -926,8 +926,8 @@ private System.Windows.Forms.Label label30; private System.Windows.Forms.Label label31; private System.Windows.Forms.Label label32; - private MyButton BUT_syncS8; - private MyButton BUT_syncS9; - private MyButton BUT_syncS10; + private ArdupilotMega.Controls.MyButton BUT_syncS8; + private ArdupilotMega.Controls.MyButton BUT_syncS9; + private ArdupilotMega.Controls.MyButton BUT_syncS10; } } \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/Radio/3DRradio.cs b/Tools/ArdupilotMegaPlanner/Radio/3DRradio.cs index d1b6f9ad9acc6843669277e32b5625a7aa0b52c6..56fdc082002c616b7461c609fd871c1f3f1d8e71 100644 --- a/Tools/ArdupilotMegaPlanner/Radio/3DRradio.cs +++ b/Tools/ArdupilotMegaPlanner/Radio/3DRradio.cs @@ -9,6 +9,8 @@ using System.Windows.Forms; using System.Net; using System.IO; using ArdupilotMega.Controls.BackstageView; +using ArdupilotMega.Arduino; +using ArdupilotMega.Comms; namespace ArdupilotMega { @@ -226,7 +228,7 @@ S13: MANCHESTER=0 private void BUT_savesettings_Click(object sender, EventArgs e) { - ArdupilotMega.ICommsSerial comPort = new SerialPort(); + ArdupilotMega.Comms.ICommsSerial comPort = new SerialPort(); try { @@ -402,7 +404,7 @@ S13: MANCHESTER=0 private void BUT_getcurrent_Click(object sender, EventArgs e) { - ArdupilotMega.ICommsSerial comPort = new SerialPort(); + ArdupilotMega.Comms.ICommsSerial comPort = new SerialPort(); try { @@ -531,7 +533,7 @@ S13: MANCHESTER=0 BUT_savesettings.Enabled = true; } - string Serial_ReadLine(ArdupilotMega.ICommsSerial comPort) + string Serial_ReadLine(ArdupilotMega.Comms.ICommsSerial comPort) { StringBuilder sb = new StringBuilder(); DateTime Deadline = DateTime.Now.AddMilliseconds(comPort.ReadTimeout); @@ -550,7 +552,7 @@ S13: MANCHESTER=0 return sb.ToString(); } - string doCommand(ArdupilotMega.ICommsSerial comPort, string cmd, int level = 0) + string doCommand(ArdupilotMega.Comms.ICommsSerial comPort, string cmd, int level = 0) { if (!comPort.IsOpen) return ""; @@ -602,7 +604,7 @@ S13: MANCHESTER=0 return ans; } - bool doConnect(ArdupilotMega.ICommsSerial comPort) + bool doConnect(ArdupilotMega.Comms.ICommsSerial comPort) { // clear buffer comPort.DiscardInBuffer(); diff --git a/Tools/ArdupilotMegaPlanner/Radio/3DRradio.resx b/Tools/ArdupilotMegaPlanner/Radio/3DRradio.resx index 99cb96659b7ba14238374113953ce98043c39f25..d13b7ec707a4a49f4e0e5ee433e46402c0e71594 100644 --- a/Tools/ArdupilotMegaPlanner/Radio/3DRradio.resx +++ b/Tools/ArdupilotMegaPlanner/Radio/3DRradio.resx @@ -1959,7 +1959,7 @@ which result in a valid packet CRC <value>BUT_savesettings</value> </data> <data name=">>BUT_savesettings.Type" xml:space="preserve"> - <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4494.22181, Culture=neutral, PublicKeyToken=null</value> + <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4494.22181, Culture=neutral, PublicKeyToken=null</value> </data> <data name=">>BUT_savesettings.Parent" xml:space="preserve"> <value>$this</value> @@ -1986,7 +1986,7 @@ which result in a valid packet CRC <value>BUT_getcurrent</value> </data> <data name=">>BUT_getcurrent.Type" xml:space="preserve"> - <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4494.22181, Culture=neutral, PublicKeyToken=null</value> + <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4494.22181, Culture=neutral, PublicKeyToken=null</value> </data> <data name=">>BUT_getcurrent.Parent" xml:space="preserve"> <value>$this</value> @@ -2037,7 +2037,7 @@ which result in a valid packet CRC <value>BUT_upload</value> </data> <data name=">>BUT_upload.Type" xml:space="preserve"> - <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4494.22181, Culture=neutral, PublicKeyToken=null</value> + <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4494.22181, Culture=neutral, PublicKeyToken=null</value> </data> <data name=">>BUT_upload.Parent" xml:space="preserve"> <value>$this</value> @@ -2061,7 +2061,7 @@ which result in a valid packet CRC <value>BUT_syncS2</value> </data> <data name=">>BUT_syncS2.Type" xml:space="preserve"> - <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4494.22181, Culture=neutral, PublicKeyToken=null</value> + <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4494.22181, Culture=neutral, PublicKeyToken=null</value> </data> <data name=">>BUT_syncS2.Parent" xml:space="preserve"> <value>$this</value> @@ -2085,7 +2085,7 @@ which result in a valid packet CRC <value>BUT_syncS3</value> </data> <data name=">>BUT_syncS3.Type" xml:space="preserve"> - <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4494.22181, Culture=neutral, PublicKeyToken=null</value> + <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4494.22181, Culture=neutral, PublicKeyToken=null</value> </data> <data name=">>BUT_syncS3.Parent" xml:space="preserve"> <value>$this</value> @@ -2109,7 +2109,7 @@ which result in a valid packet CRC <value>BUT_syncS5</value> </data> <data name=">>BUT_syncS5.Type" xml:space="preserve"> - <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4494.22181, Culture=neutral, PublicKeyToken=null</value> + <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4494.22181, Culture=neutral, PublicKeyToken=null</value> </data> <data name=">>BUT_syncS5.Parent" xml:space="preserve"> <value>$this</value> @@ -2715,7 +2715,7 @@ which result in a valid packet CRC <value>BUT_syncS8</value> </data> <data name=">>BUT_syncS8.Type" xml:space="preserve"> - <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4494.22181, Culture=neutral, PublicKeyToken=null</value> + <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4494.22181, Culture=neutral, PublicKeyToken=null</value> </data> <data name=">>BUT_syncS8.Parent" xml:space="preserve"> <value>$this</value> @@ -2742,7 +2742,7 @@ which result in a valid packet CRC <value>BUT_syncS9</value> </data> <data name=">>BUT_syncS9.Type" xml:space="preserve"> - <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4494.22181, Culture=neutral, PublicKeyToken=null</value> + <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4494.22181, Culture=neutral, PublicKeyToken=null</value> </data> <data name=">>BUT_syncS9.Parent" xml:space="preserve"> <value>$this</value> @@ -2769,7 +2769,7 @@ which result in a valid packet CRC <value>BUT_syncS10</value> </data> <data name=">>BUT_syncS10.Type" xml:space="preserve"> - <value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.1.4494.22181, Culture=neutral, PublicKeyToken=null</value> + <value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner, Version=1.1.4494.22181, Culture=neutral, PublicKeyToken=null</value> </data> <data name=">>BUT_syncS10.Parent" xml:space="preserve"> <value>$this</value> diff --git a/Tools/ArdupilotMegaPlanner/SerialInput.Designer.cs b/Tools/ArdupilotMegaPlanner/SerialInput.Designer.cs index babfd7e31572c9f2a9e9c3b4f816b4a38f76033e..06d99e0a851c488ea83bba3ce1fce94fa168cede 100644 --- a/Tools/ArdupilotMegaPlanner/SerialInput.Designer.cs +++ b/Tools/ArdupilotMegaPlanner/SerialInput.Designer.cs @@ -30,7 +30,7 @@ { System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(SerialInput)); this.CMB_serialport = new System.Windows.Forms.ComboBox(); - this.BUT_connect = new ArdupilotMega.MyButton(); + this.BUT_connect = new ArdupilotMega.Controls.MyButton(); this.CMB_baudrate = new System.Windows.Forms.ComboBox(); this.label1 = new System.Windows.Forms.Label(); this.LBL_location = new System.Windows.Forms.Label(); @@ -125,7 +125,7 @@ #endregion private System.Windows.Forms.ComboBox CMB_serialport; - private MyButton BUT_connect; + private ArdupilotMega.Controls.MyButton BUT_connect; private System.Windows.Forms.ComboBox CMB_baudrate; private System.Windows.Forms.Label label1; private System.Windows.Forms.Label LBL_location; diff --git a/Tools/ArdupilotMegaPlanner/SerialOutput.Designer.cs b/Tools/ArdupilotMegaPlanner/SerialOutput.Designer.cs index 099d4b32b56efca4ea82bf62ba437a9f883cfb3b..1f57d7eefd93e15724453dd86ff268234bad02a3 100644 --- a/Tools/ArdupilotMegaPlanner/SerialOutput.Designer.cs +++ b/Tools/ArdupilotMegaPlanner/SerialOutput.Designer.cs @@ -30,7 +30,7 @@ { System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(SerialOutput)); this.CMB_serialport = new System.Windows.Forms.ComboBox(); - this.BUT_connect = new ArdupilotMega.MyButton(); + this.BUT_connect = new ArdupilotMega.Controls.MyButton(); this.CMB_baudrate = new System.Windows.Forms.ComboBox(); this.SuspendLayout(); // @@ -90,7 +90,7 @@ #endregion private System.Windows.Forms.ComboBox CMB_serialport; - private MyButton BUT_connect; + private ArdupilotMega.Controls.MyButton BUT_connect; private System.Windows.Forms.ComboBox CMB_baudrate; } } \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/ThemeManager.cs b/Tools/ArdupilotMegaPlanner/ThemeManager.cs index 859cd8e7d4411e328920bb4ccc8d3a04e4ab9eda..c15b74ec62bacae1065af70cd9f47fec6c0ef836 100644 --- a/Tools/ArdupilotMegaPlanner/ThemeManager.cs +++ b/Tools/ArdupilotMegaPlanner/ThemeManager.cs @@ -3,6 +3,7 @@ using System.Drawing; using System.Windows.Forms; using ArdupilotMega.Controls.BackstageView; using log4net; +using ArdupilotMega.Controls; namespace ArdupilotMega { @@ -84,7 +85,7 @@ namespace ArdupilotMega { Color PrimeColor = Color.FromArgb(0x94, 0xc1, 0x1f); - MyButton but = (MyButton)ctl; + ArdupilotMega.Controls.MyButton but = (MyButton)ctl; //but.BGGradTop = Color.FromArgb(PrimeColor.R, PrimeColor.G, PrimeColor.B); //but.BGGradBot = Color.FromArgb(255 - (int)(PrimeColor.R * 0.27), 255 - (int)(PrimeColor.G * 0.14), 255 - (int)(PrimeColor.B * 0.79)); //but.ForeColor = Color.FromArgb(0x40, 0x57, 0x04); //Color.FromArgb(255 - (int)(PrimeColor.R * 0.7), 255 - (int)(PrimeColor.G * 0.8), 255 - (int)(PrimeColor.B * 0.1)); diff --git a/Tools/ArdupilotMegaPlanner/Updater/Updater.csproj b/Tools/ArdupilotMegaPlanner/Updater/Updater.csproj index 8b7bd960df71064e927cde302631a024904f0afb..11c4d121c40274c91ac917426854600a17467c84 100644 --- a/Tools/ArdupilotMegaPlanner/Updater/Updater.csproj +++ b/Tools/ArdupilotMegaPlanner/Updater/Updater.csproj @@ -56,7 +56,8 @@ <SignAssembly>false</SignAssembly> </PropertyGroup> <PropertyGroup> - <AssemblyOriginatorKeyFile>mykey.pfx</AssemblyOriginatorKeyFile> + <AssemblyOriginatorKeyFile> + </AssemblyOriginatorKeyFile> </PropertyGroup> <ItemGroup> <Reference Include="System" /> @@ -80,7 +81,6 @@ <DesignTime>True</DesignTime> </Compile> <None Include="app.config" /> - <None Include="mykey.pfx" /> <None Include="Properties\Settings.settings"> <Generator>SettingsSingleFileGenerator</Generator> <LastGenOutput>Settings.Designer.cs</LastGenOutput> diff --git a/Tools/ArdupilotMegaPlanner/bin/Release/ArdupilotMegaPlanner.pdb b/Tools/ArdupilotMegaPlanner/bin/Release/ArdupilotMegaPlanner.pdb index cd53d0368abba016576d826c794c617f3e7eacb3..b4768625fb68b6190a5e5250b74a477d28298884 100644 Binary files a/Tools/ArdupilotMegaPlanner/bin/Release/ArdupilotMegaPlanner.pdb and b/Tools/ArdupilotMegaPlanner/bin/Release/ArdupilotMegaPlanner.pdb differ diff --git a/Tools/ArdupilotMegaPlanner/bin/Release/aircraft/arducopter/Models/_propeller0_.skb b/Tools/ArdupilotMegaPlanner/bin/Release/aircraft/arducopter/Models/_propeller0_.skb deleted file mode 100644 index 700b26fc31b08bcf5a75f298ce80e6115710d7a1..0000000000000000000000000000000000000000 Binary files a/Tools/ArdupilotMegaPlanner/bin/Release/aircraft/arducopter/Models/_propeller0_.skb and /dev/null differ diff --git a/Tools/ArdupilotMegaPlanner/bin/Release/aircraft/arducopter/Models/_propeller0_.skp b/Tools/ArdupilotMegaPlanner/bin/Release/aircraft/arducopter/Models/_propeller0_.skp deleted file mode 100644 index d525f6e3f18177d89e61ed3a8c1a322f9dfb169e..0000000000000000000000000000000000000000 Binary files a/Tools/ArdupilotMegaPlanner/bin/Release/aircraft/arducopter/Models/_propeller0_.skp and /dev/null differ diff --git a/Tools/ArdupilotMegaPlanner/bin/Release/version.txt b/Tools/ArdupilotMegaPlanner/bin/Release/version.txt index 061ff9cbb6cf009b0e343f521f1eda8671039359..0b1ae78e9c1899a5f2a3c0a5001288850fca748c 100644 --- a/Tools/ArdupilotMegaPlanner/bin/Release/version.txt +++ b/Tools/ArdupilotMegaPlanner/bin/Release/version.txt @@ -1 +1 @@ -1.1.4496.35998 \ No newline at end of file +1.1.4494.38818 \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/georefimage.cs b/Tools/ArdupilotMegaPlanner/georefimage.cs index 17c166f02e383982facbaa1a348676ff4ec0ed2c..21b6374671640bf3118a50c08e5bbd2cad6b140e 100644 --- a/Tools/ArdupilotMegaPlanner/georefimage.cs +++ b/Tools/ArdupilotMegaPlanner/georefimage.cs @@ -19,16 +19,16 @@ namespace ArdupilotMega { private static readonly ILog log = LogManager.GetLogger(MethodBase.GetCurrentMethod().DeclaringType); private OpenFileDialog openFileDialog1; - private MyButton BUT_browselog; - private MyButton BUT_browsedir; + private ArdupilotMega.Controls.MyButton BUT_browselog; + private ArdupilotMega.Controls.MyButton BUT_browsedir; private TextBox TXT_logfile; private TextBox TXT_jpgdir; private TextBox TXT_offsetseconds; - private MyButton BUT_doit; + private ArdupilotMega.Controls.MyButton BUT_doit; private FolderBrowserDialog folderBrowserDialog1; private Label label1; private TextBox TXT_outputlog; - private MyButton BUT_estoffset; + private ArdupilotMega.Controls.MyButton BUT_estoffset; int latpos = 4, lngpos = 5, altpos = 7, cogpos = 9; private NumericUpDown numericUpDown1; @@ -40,7 +40,7 @@ namespace ArdupilotMega private Label label4; private Label label5; private Label label6; - private MyButton BUT_Geotagimages; + private ArdupilotMega.Controls.MyButton BUT_Geotagimages; internal Georefimage() { InitializeComponent(); @@ -419,11 +419,11 @@ namespace ArdupilotMega this.folderBrowserDialog1 = new System.Windows.Forms.FolderBrowserDialog(); this.TXT_outputlog = new System.Windows.Forms.TextBox(); this.label1 = new System.Windows.Forms.Label(); - this.BUT_Geotagimages = new ArdupilotMega.MyButton(); - this.BUT_estoffset = new ArdupilotMega.MyButton(); - this.BUT_doit = new ArdupilotMega.MyButton(); - this.BUT_browsedir = new ArdupilotMega.MyButton(); - this.BUT_browselog = new ArdupilotMega.MyButton(); + this.BUT_Geotagimages = new ArdupilotMega.Controls.MyButton(); + this.BUT_estoffset = new ArdupilotMega.Controls.MyButton(); + this.BUT_doit = new ArdupilotMega.Controls.MyButton(); + this.BUT_browsedir = new ArdupilotMega.Controls.MyButton(); + this.BUT_browselog = new ArdupilotMega.Controls.MyButton(); this.numericUpDown1 = new System.Windows.Forms.NumericUpDown(); this.numericUpDown2 = new System.Windows.Forms.NumericUpDown(); this.numericUpDown3 = new System.Windows.Forms.NumericUpDown(); diff --git a/Tools/ArdupilotMegaPlanner/paramcompare.Designer.cs b/Tools/ArdupilotMegaPlanner/paramcompare.Designer.cs index 8e87811847128d6e63a7e118d5392ebfe5cd12f7..2d90d5f5d04b7e38584fc33304c15e72a311f88a 100644 --- a/Tools/ArdupilotMegaPlanner/paramcompare.Designer.cs +++ b/Tools/ArdupilotMegaPlanner/paramcompare.Designer.cs @@ -34,7 +34,7 @@ this.Value = new System.Windows.Forms.DataGridViewTextBoxColumn(); this.newvalue = new System.Windows.Forms.DataGridViewTextBoxColumn(); this.Use = new System.Windows.Forms.DataGridViewCheckBoxColumn(); - this.BUT_save = new ArdupilotMega.MyButton(); + this.BUT_save = new ArdupilotMega.Controls.MyButton(); this.CHK_toggleall = new System.Windows.Forms.CheckBox(); ((System.ComponentModel.ISupportInitialize)(this.Params)).BeginInit(); this.SuspendLayout(); @@ -124,7 +124,7 @@ #endregion private System.Windows.Forms.DataGridView Params; - private MyButton BUT_save; + private ArdupilotMega.Controls.MyButton BUT_save; private System.Windows.Forms.DataGridViewTextBoxColumn Command; private System.Windows.Forms.DataGridViewTextBoxColumn Value; private System.Windows.Forms.DataGridViewTextBoxColumn newvalue; diff --git a/Tools/ArdupilotMegaPlanner/temp.Designer.cs b/Tools/ArdupilotMegaPlanner/temp.Designer.cs index 767443ebc44368746d1461e69fdd913df24fe8a2..1f5e4d0834ec36dd3a408939704ce32dd002511e 100644 --- a/Tools/ArdupilotMegaPlanner/temp.Designer.cs +++ b/Tools/ArdupilotMegaPlanner/temp.Designer.cs @@ -28,26 +28,26 @@ /// </summary> private void InitializeComponent() { - this.button1 = new ArdupilotMega.MyButton(); - this.BUT_wipeeeprom = new ArdupilotMega.MyButton(); - this.BUT_flashdl = new ArdupilotMega.MyButton(); - this.BUT_flashup = new ArdupilotMega.MyButton(); - this.BUT_dleeprom = new ArdupilotMega.MyButton(); - this.BUT_copy1280 = new ArdupilotMega.MyButton(); - this.BUT_copy2560 = new ArdupilotMega.MyButton(); - this.BUT_copyto2560 = new ArdupilotMega.MyButton(); - this.BUT_copyto1280 = new ArdupilotMega.MyButton(); - this.button2 = new ArdupilotMega.MyButton(); + this.button1 = new ArdupilotMega.Controls.MyButton(); + this.BUT_wipeeeprom = new ArdupilotMega.Controls.MyButton(); + this.BUT_flashdl = new ArdupilotMega.Controls.MyButton(); + this.BUT_flashup = new ArdupilotMega.Controls.MyButton(); + this.BUT_dleeprom = new ArdupilotMega.Controls.MyButton(); + this.BUT_copy1280 = new ArdupilotMega.Controls.MyButton(); + this.BUT_copy2560 = new ArdupilotMega.Controls.MyButton(); + this.BUT_copyto2560 = new ArdupilotMega.Controls.MyButton(); + this.BUT_copyto1280 = new ArdupilotMega.Controls.MyButton(); + this.button2 = new ArdupilotMega.Controls.MyButton(); this.label1 = new System.Windows.Forms.Label(); this.label2 = new System.Windows.Forms.Label(); this.label3 = new System.Windows.Forms.Label(); - this.BUT_geinjection = new ArdupilotMega.MyButton(); - this.BUT_clearcustommaps = new ArdupilotMega.MyButton(); - this.BUT_lang_edit = new ArdupilotMega.MyButton(); - this.BUT_georefimage = new ArdupilotMega.MyButton(); - this.BUT_follow_me = new ArdupilotMega.MyButton(); - this.BUT_ant_track = new ArdupilotMega.MyButton(); - this.BUT_magcalib = new ArdupilotMega.MyButton(); + this.BUT_geinjection = new ArdupilotMega.Controls.MyButton(); + this.BUT_clearcustommaps = new ArdupilotMega.Controls.MyButton(); + this.BUT_lang_edit = new ArdupilotMega.Controls.MyButton(); + this.BUT_georefimage = new ArdupilotMega.Controls.MyButton(); + this.BUT_follow_me = new ArdupilotMega.Controls.MyButton(); + this.BUT_ant_track = new ArdupilotMega.Controls.MyButton(); + this.BUT_magcalib = new ArdupilotMega.Controls.MyButton(); this.SuspendLayout(); // // button1 @@ -279,26 +279,26 @@ #endregion - private MyButton button1; - private MyButton BUT_wipeeeprom; - private MyButton BUT_flashdl; - private MyButton BUT_flashup; - private MyButton BUT_dleeprom; - private MyButton BUT_copy1280; - private MyButton BUT_copy2560; - private MyButton BUT_copyto2560; - private MyButton BUT_copyto1280; - private MyButton button2; + private ArdupilotMega.Controls.MyButton button1; + private ArdupilotMega.Controls.MyButton BUT_wipeeeprom; + private ArdupilotMega.Controls.MyButton BUT_flashdl; + private ArdupilotMega.Controls.MyButton BUT_flashup; + private ArdupilotMega.Controls.MyButton BUT_dleeprom; + private ArdupilotMega.Controls.MyButton BUT_copy1280; + private ArdupilotMega.Controls.MyButton BUT_copy2560; + private ArdupilotMega.Controls.MyButton BUT_copyto2560; + private ArdupilotMega.Controls.MyButton BUT_copyto1280; + private ArdupilotMega.Controls.MyButton button2; private System.Windows.Forms.Label label1; private System.Windows.Forms.Label label2; private System.Windows.Forms.Label label3; - private MyButton BUT_geinjection; - private MyButton BUT_clearcustommaps; - private MyButton BUT_lang_edit; - private MyButton BUT_georefimage; - private MyButton BUT_follow_me; - private MyButton BUT_ant_track; - private MyButton BUT_magcalib; + private ArdupilotMega.Controls.MyButton BUT_geinjection; + private ArdupilotMega.Controls.MyButton BUT_clearcustommaps; + private ArdupilotMega.Controls.MyButton BUT_lang_edit; + private ArdupilotMega.Controls.MyButton BUT_georefimage; + private ArdupilotMega.Controls.MyButton BUT_follow_me; + private ArdupilotMega.Controls.MyButton BUT_ant_track; + private ArdupilotMega.Controls.MyButton BUT_magcalib; //private SharpVectors.Renderers.Forms.SvgPictureBox svgPictureBox1; } diff --git a/Tools/ArdupilotMegaPlanner/temp.cs b/Tools/ArdupilotMegaPlanner/temp.cs index 219e468aec1494758af7641678bde7e9e83903fa..28e7bb4dc27d36a4c4ab32c16bbfc5c9819a47f4 100644 --- a/Tools/ArdupilotMegaPlanner/temp.cs +++ b/Tools/ArdupilotMegaPlanner/temp.cs @@ -16,6 +16,7 @@ using GMap.NET.CacheProviders; using log4net; using System.Security.Permissions; +using ArdupilotMega.Arduino; namespace ArdupilotMega { diff --git a/Tools/ArdupilotMegaPlanner/test.cs b/Tools/ArdupilotMegaPlanner/test.cs deleted file mode 100644 index 5f282702bb03ef11d7184d19c80927b47f919764..0000000000000000000000000000000000000000 --- a/Tools/ArdupilotMegaPlanner/test.cs +++ /dev/null @@ -1 +0,0 @@ - \ No newline at end of file diff --git a/Tools/autotest/pysim/sim_multicopter.py b/Tools/autotest/pysim/sim_multicopter.py index 803e5f1e2c0a2bcfbb911e91d8118d32bd8e38fb..95e190264eda5e76baecf1719adbdfbbdcaa3398 100755 --- a/Tools/autotest/pysim/sim_multicopter.py +++ b/Tools/autotest/pysim/sim_multicopter.py @@ -5,14 +5,6 @@ import util, time, os, sys, math import socket, struct import select, fgFDM, errno -# find the mavlink.py module -for d in [ 'pymavlink', - os.path.join(os.path.dirname(os.path.realpath(__file__)), '../pymavlink') ]: - if os.path.exists(d): - sys.path.insert(0, d) -import mavlink - - def sim_send(m, a): '''send flight information to mavproxy and flightgear''' global fdm diff --git a/Tools/autotest/sim_arducopter10.sh b/Tools/autotest/sim_arducopter10.sh new file mode 100755 index 0000000000000000000000000000000000000000..262fd6de09ea9e39d9979ad850439695ffaa9a91 --- /dev/null +++ b/Tools/autotest/sim_arducopter10.sh @@ -0,0 +1,39 @@ +#!/bin/bash + +set -e +set -x + +if [ $# -eq 1 ]; then + frame="$1" + target="sitl-$frame" +else + frame="+" + target="sitl" +fi + +case $frame in + +,X,quad) + target="sitl" + ;; + octa) + target="sitl-octa" + ;; +esac + +echo "Building with target $target for frame $frame" + +autotest=$(dirname $(readlink -e $0)) +pushd $autotest/../../ArduCopter +make clean $target-mavlink10 + +tfile=$(tempfile) +echo r > $tfile +#gnome-terminal -e "gdb -x $tfile --args /tmp/ArduCopter.build/ArduCopter.elf" +gnome-terminal -e /tmp/ArduCopter.build/ArduCopter.elf +#gnome-terminal -e "valgrind -q /tmp/ArduCopter.build/ArduCopter.elf" +sleep 2 +rm -f $tfile +gnome-terminal -e "../Tools/autotest/pysim/sim_multicopter.py --frame=$frame --home=-35.362938,149.165085,584,270" +sleep 2 +popd +mavproxy.py --master tcp:127.0.0.1:5760 --sitl 127.0.0.1:5501 --out 127.0.0.1:14550 --out 127.0.0.1:14551 --quadcopter --mav10 diff --git a/Tools/scripts/build_all.sh b/Tools/scripts/build_all.sh index e32924b56253ad179f9540080ac80e9bd72badbb..d246a8d9d04533b203125fcfa6c36e80ff2fd91b 100755 --- a/Tools/scripts/build_all.sh +++ b/Tools/scripts/build_all.sh @@ -8,7 +8,7 @@ set -x echo "Testing ArduPlane build" pushd ArduPlane -for b in all apm2 apm2beta hil hilsensors mavlink10 sitl; do +for b in all apm2 apm2beta hil hilsensors mavlink10 sitl sitl-mavlink10 sitl-mount; do pwd make clean make $b diff --git a/libraries/APM_RC/APM_RC.h b/libraries/APM_RC/APM_RC.h index 36a467e302a1e8e934224993d6e7ac13c20eb1f7..9882b8eca68539441e9e667309779cef93e9a460 100644 --- a/libraries/APM_RC/APM_RC.h +++ b/libraries/APM_RC/APM_RC.h @@ -36,6 +36,7 @@ class APM_RC_Class virtual void Init( Arduino_Mega_ISR_Registry * isr_reg ) = 0; virtual void OutputCh(uint8_t ch, uint16_t pwm) = 0; + virtual uint16_t OutputCh_current(uint8_t ch) = 0; virtual uint16_t InputCh(uint8_t ch) = 0; virtual uint8_t GetState() = 0; virtual void clearOverride(void) = 0; diff --git a/libraries/APM_RC/APM_RC_APM1.cpp b/libraries/APM_RC/APM_RC_APM1.cpp index 437037817852e1c24fdf6c2be5fed16ed19b8dfc..2bc8a20cf4929850351537f15c4411323a48152b 100644 --- a/libraries/APM_RC/APM_RC_APM1.cpp +++ b/libraries/APM_RC/APM_RC_APM1.cpp @@ -157,6 +157,25 @@ void APM_RC_APM1::OutputCh(uint8_t ch, uint16_t pwm) } } +uint16_t APM_RC_APM1::OutputCh_current(uint8_t ch) +{ + uint16_t pwm=0; + switch(ch) { + case 0: pwm=OCR5B; break; //ch1 + case 1: pwm=OCR5C; break; //ch2 + case 2: pwm=OCR1B; break; //ch3 + case 3: pwm=OCR1C; break; //ch4 + case 4: pwm=OCR4C; break; //ch5 + case 5: pwm=OCR4B; break; //ch6 + case 6: pwm=OCR3C; break; //ch7 + case 7: pwm=OCR3B; break; //ch8 + case 8: pwm=OCR5A; break; //ch9, PL3 + case 9: pwm=OCR1A; break; //ch10, PB5 + case 10: pwm=OCR3A; break; //ch11, PE3 + } + return pwm>>1; +} + void APM_RC_APM1::enable_out(uint8_t ch) { switch(ch){ diff --git a/libraries/APM_RC/APM_RC_APM1.h b/libraries/APM_RC/APM_RC_APM1.h index c448a3eddd43cec2b01b3bf18ceca799313b987b..945150f57aeeace671cfe548896a153702ee7799 100644 --- a/libraries/APM_RC/APM_RC_APM1.h +++ b/libraries/APM_RC/APM_RC_APM1.h @@ -13,6 +13,7 @@ class APM_RC_APM1 : public APM_RC_Class APM_RC_APM1(); void Init( Arduino_Mega_ISR_Registry * isr_reg ); void OutputCh(uint8_t ch, uint16_t pwm); + uint16_t OutputCh_current(uint8_t ch); uint16_t InputCh(uint8_t ch); uint8_t GetState(); bool setHIL(int16_t v[NUM_CHANNELS]); diff --git a/libraries/APM_RC/APM_RC_APM2.cpp b/libraries/APM_RC/APM_RC_APM2.cpp index 0a728cf4f4ec2f8c506c86d9efb34b7ceb73a022..62fad722b68a467a8631d8a5d0569dff621afaa3 100644 --- a/libraries/APM_RC/APM_RC_APM2.cpp +++ b/libraries/APM_RC/APM_RC_APM2.cpp @@ -161,6 +161,24 @@ void APM_RC_APM2::OutputCh(unsigned char ch, uint16_t pwm) } } +uint16_t APM_RC_APM2::OutputCh_current(uint8_t ch) +{ + uint16_t pwm=0; + switch(ch){ + case 0: pwm=OCR1B; break; // out1 + case 1: pwm=OCR1A; break; // out2 + case 2: pwm=OCR4C; break; // out3 + case 3: pwm=OCR4B; break; // out4 + case 4: pwm=OCR4A; break; // out5 + case 5: pwm=OCR3C; break; // out6 + case 6: pwm=OCR3B; break; // out7 + case 7: pwm=OCR3A; break; // out8 + case 9: pwm=OCR5B; break; // out10 + case 10: pwm=OCR5C; break; // out11 + } + return pwm>>1; +} + void APM_RC_APM2::enable_out(uint8_t ch) { switch(ch) { diff --git a/libraries/APM_RC/APM_RC_APM2.h b/libraries/APM_RC/APM_RC_APM2.h index f2a93a1f0784042ba387b14155cac45a0d515cf8..a6743c1a5ab05849d58c012a0e8e71ff4d737b5e 100644 --- a/libraries/APM_RC/APM_RC_APM2.h +++ b/libraries/APM_RC/APM_RC_APM2.h @@ -14,7 +14,8 @@ class APM_RC_APM2 : public APM_RC_Class public: APM_RC_APM2(); void Init( Arduino_Mega_ISR_Registry * isr_reg ); - void OutputCh(unsigned char ch, uint16_t pwm); + void OutputCh(uint8_t ch, uint16_t pwm); + uint16_t OutputCh_current(uint8_t ch); uint16_t InputCh(unsigned char ch); unsigned char GetState(); bool setHIL(int16_t v[NUM_CHANNELS]); diff --git a/libraries/Desktop/support/sitl.cpp b/libraries/Desktop/support/sitl.cpp index 9ee53f44401790d9ccdb0d83632bc3269fe5aaaa..ab7ab16f9c3348ccd815f9b6565ff7f107584772 100644 --- a/libraries/Desktop/support/sitl.cpp +++ b/libraries/Desktop/support/sitl.cpp @@ -344,6 +344,16 @@ void sitl_simstate_send(uint8_t chan) { double p, q, r; float yaw; + extern 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); // we want the gyro values to be directly comparable to the // raw_imu message, which is in body frame @@ -357,12 +367,12 @@ void sitl_simstate_send(uint8_t chan) yaw -= 360; } - mavlink_msg_simstate_send((mavlink_channel_t)chan, - ToRad(sim_state.rollDeg), - ToRad(sim_state.pitchDeg), - ToRad(yaw), - sim_state.xAccel, - sim_state.yAccel, - sim_state.zAccel, - p, q, r); + mavlink_simstate_send(chan, + ToRad(sim_state.rollDeg), + ToRad(sim_state.pitchDeg), + ToRad(yaw), + sim_state.xAccel, + sim_state.yAccel, + sim_state.zAccel, + p, q, r); } diff --git a/libraries/GCS_MAVLink/GCS_MAVLink.cpp b/libraries/GCS_MAVLink/GCS_MAVLink.cpp deleted file mode 100644 index fa8759f1e72d714a1cc8bab2ec3ef3bde322c2b3..0000000000000000000000000000000000000000 --- a/libraries/GCS_MAVLink/GCS_MAVLink.cpp +++ /dev/null @@ -1,27 +0,0 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*- - -/// @file GCS_MAVLink.cpp -/// @brief Supporting bits for MAVLink. - -#include "GCS_MAVLink.h" - -BetterStream *mavlink_comm_0_port; -BetterStream *mavlink_comm_1_port; - -// this might need to move to the flight software -mavlink_system_t mavlink_system = {7,1,0,0}; - -#ifdef MAVLINK10 -# include "include/mavlink/v1.0/mavlink_helpers.h" -#else -# include "include/mavlink/v0.9/mavlink_helpers.h" -#endif - -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 -} diff --git a/libraries/GCS_MAVLink/GCS_MAVLink.h b/libraries/GCS_MAVLink/GCS_MAVLink.h index d2003b84fa760445edd3b9e467d16fc658e790cc..6e85053094f8d43678f223d647f5b684d43984bf 100644 --- a/libraries/GCS_MAVLink/GCS_MAVLink.h +++ b/libraries/GCS_MAVLink/GCS_MAVLink.h @@ -8,7 +8,9 @@ #include <BetterStream.h> -#define MAVLINK_SEPARATE_HELPERS +// we have separate helpers disabled to make it possible +// to select MAVLink 1.0 in the arduino GUI build +//#define MAVLINK_SEPARATE_HELPERS #ifdef MAVLINK10 # include "include/mavlink/v1.0/ardupilotmega/version.h" diff --git a/libraries/GCS_MAVLink/Mavlink_compat.h b/libraries/GCS_MAVLink/Mavlink_compat.h index c53544721ab8c829dac5dbafeb04378aea1179fa..2685669c8ca9d8ff8a132b8c25b74695f503a132 100644 --- a/libraries/GCS_MAVLink/Mavlink_compat.h +++ b/libraries/GCS_MAVLink/Mavlink_compat.h @@ -53,6 +53,8 @@ #define mavlink_msg_waypoint_set_current_decode mavlink_msg_mission_set_current_decode #define mavlink_waypoint_set_current_t mavlink_mission_set_current_t +#define MAV_CMD_DO_SET_ROI MAV_CMD_NAV_ROI + static uint8_t mav_var_type(enum ap_var_type t) { if (t == AP_PARAM_INT8) { diff --git a/libraries/GCS_MAVLink/include/mavlink/v0.9/ardupilotmega/version.h b/libraries/GCS_MAVLink/include/mavlink/v0.9/ardupilotmega/version.h index cbf2f9b1ed5fecfa40ce4d98e7595ca966fa9aa9..319b4dbed0176e8bdadb6939bac3f0d1d48ab594 100644 --- a/libraries/GCS_MAVLink/include/mavlink/v0.9/ardupilotmega/version.h +++ b/libraries/GCS_MAVLink/include/mavlink/v0.9/ardupilotmega/version.h @@ -5,7 +5,7 @@ #ifndef MAVLINK_VERSION_H #define MAVLINK_VERSION_H -#define MAVLINK_BUILD_DATE "Fri Apr 20 12:22:46 2012" +#define MAVLINK_BUILD_DATE "Tue Apr 24 10:29:51 2012" #define MAVLINK_WIRE_PROTOCOL_VERSION "0.9" #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 101 diff --git a/libraries/GCS_MAVLink/include/mavlink/v0.9/checksum.h b/libraries/GCS_MAVLink/include/mavlink/v0.9/checksum.h index b70991f5ab7c46163f7d13c6e11f70e5102b2457..4f4cce02fc91ae78f851d7dcb1ec65fa4dd1f526 100644 --- a/libraries/GCS_MAVLink/include/mavlink/v0.9/checksum.h +++ b/libraries/GCS_MAVLink/include/mavlink/v0.9/checksum.h @@ -52,7 +52,7 @@ static inline void crc_init(uint16_t* crcAccum) * @param length length of the byte array * @return the checksum over the buffer bytes **/ -static inline uint16_t crc_calculate(uint8_t* pBuffer, uint16_t length) +static inline uint16_t crc_calculate(const uint8_t* pBuffer, uint16_t length) { uint16_t crcTmp; crc_init(&crcTmp); diff --git a/libraries/GCS_MAVLink/include/mavlink/v0.9/common/common.h b/libraries/GCS_MAVLink/include/mavlink/v0.9/common/common.h index 84538ed57013b0dd08896d6c8962924d8c55328a..210baad49ba866814d76e179799b3f1b43a89927 100644 --- a/libraries/GCS_MAVLink/include/mavlink/v0.9/common/common.h +++ b/libraries/GCS_MAVLink/include/mavlink/v0.9/common/common.h @@ -43,55 +43,6 @@ extern "C" { // ENUM DEFINITIONS -/** @brief Commands to be executed by the MAV. They can be executed on user request, - or as part of a mission script. If the action is used in a mission, the parameter mapping - to the waypoint/mission message is as follows: - Param 1, Param 2, Param 3, Param 4, X: Param 5, Y:Param 6, Z:Param 7. This command list is similar what - ARINC 424 is for commercial aircraft: A data format how to interpret waypoint/mission data. */ -#ifndef HAVE_ENUM_MAV_CMD -#define HAVE_ENUM_MAV_CMD -enum MAV_CMD -{ - MAV_CMD_NAV_WAYPOINT=16, /* Navigate to waypoint. |Hold time in decimal seconds. (ignored by fixed wing, time to stay at waypoint for rotary wing)| Acceptance radius in meters (if the sphere with this radius is hit, the waypoint counts as reached)| 0 to pass through the WP, if > 0 radius in meters to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control.| Desired yaw angle at waypoint (rotary wing)| Latitude| Longitude| Altitude| */ - MAV_CMD_NAV_LOITER_UNLIM=17, /* Loiter around this waypoint an unlimited amount of time |Empty| Empty| Radius around waypoint, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */ - MAV_CMD_NAV_LOITER_TURNS=18, /* Loiter around this waypoint for X turns |Turns| Empty| Radius around waypoint, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */ - MAV_CMD_NAV_LOITER_TIME=19, /* Loiter around this waypoint for X seconds |Seconds (decimal)| Empty| Radius around waypoint, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */ - MAV_CMD_NAV_RETURN_TO_LAUNCH=20, /* Return to launch location |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_NAV_LAND=21, /* Land at location |Empty| Empty| Empty| Desired yaw angle.| Latitude| Longitude| Altitude| */ - MAV_CMD_NAV_TAKEOFF=22, /* Takeoff from ground / hand |Minimum pitch (if airspeed sensor present), desired pitch without sensor| Empty| Empty| Yaw angle (if magnetometer present), ignored without magnetometer| Latitude| Longitude| Altitude| */ - MAV_CMD_NAV_ROI=80, /* Sets the region of interest (ROI) for a sensor set or the - vehicle itself. This can then be used by the vehicles control - system to control the vehicle attitude and the attitude of various - sensors such as cameras. |Region of intereset mode. (see MAV_ROI enum)| Waypoint index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple ROI's)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z| */ - MAV_CMD_NAV_PATHPLANNING=81, /* Control autonomous path planning on the MAV. |0: Disable local obstacle avoidance / local path planning (without resetting map), 1: Enable local path planning, 2: Enable and reset local path planning| 0: Disable full path planning (without resetting map), 1: Enable, 2: Enable and reset map/occupancy grid, 3: Enable and reset planned route, but not occupancy grid| Empty| Yaw angle at goal, in compass degrees, [0..360]| Latitude/X of goal| Longitude/Y of goal| Altitude/Z of goal| */ - MAV_CMD_NAV_LAST=95, /* NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_CONDITION_DELAY=112, /* Delay mission state machine. |Delay in seconds (decimal)| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_CONDITION_CHANGE_ALT=113, /* Ascend/descend at rate. Delay mission state machine until desired altitude reached. |Descent / Ascend rate (m/s)| Empty| Empty| Empty| Empty| Empty| Finish Altitude| */ - MAV_CMD_CONDITION_DISTANCE=114, /* Delay mission state machine until within desired distance of next NAV point. |Distance (meters)| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_CONDITION_YAW=115, /* Reach a certain target angle. |target angle: [0-360], 0 is north| speed during yaw change:[deg per second]| direction: negative: counter clockwise, positive: clockwise [-1,1]| relative offset or absolute angle: [ 1,0]| Empty| Empty| Empty| */ - MAV_CMD_CONDITION_LAST=159, /* NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_SET_MODE=176, /* Set system mode. |Mode, as defined by ENUM MAV_MODE| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_JUMP=177, /* Jump to the desired command in the mission list. Repeat this action only the specified number of times |Sequence number| Repeat count| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_CHANGE_SPEED=178, /* Change speed and/or throttle set points. |Speed type (0=Airspeed, 1=Ground Speed)| Speed (m/s, -1 indicates no change)| Throttle ( Percent, -1 indicates no change)| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_SET_HOME=179, /* Changes the home location either to the current location or a specified location. |Use current (1=use current location, 0=use specified location)| Empty| Empty| Empty| Latitude| Longitude| Altitude| */ - MAV_CMD_DO_SET_PARAMETER=180, /* Set a system parameter. Caution! Use of this command requires knowledge of the numeric enumeration value of the parameter. |Parameter number| Parameter value| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_SET_RELAY=181, /* Set a relay to a condition. |Relay number| Setting (1=on, 0=off, others possible depending on system hardware)| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_REPEAT_RELAY=182, /* Cycle a relay on and off for a desired number of cyles with a desired period. |Relay number| Cycle count| Cycle time (seconds, decimal)| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_SET_SERVO=183, /* Set a servo to a desired PWM value. |Servo number| PWM (microseconds, 1000 to 2000 typical)| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_REPEAT_SERVO=184, /* Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period. |Servo number| PWM (microseconds, 1000 to 2000 typical)| Cycle count| Cycle time (seconds)| Empty| Empty| Empty| */ - MAV_CMD_DO_CONTROL_VIDEO=200, /* Control onboard camera capturing. |Camera ID (-1 for all)| Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw| Transmission mode: 0: video stream, >0: single images every n seconds (decimal)| Recording: 0: disabled, 1: enabled compressed, 2: enabled raw| Empty| Empty| Empty| */ - MAV_CMD_DO_SET_ROI=201, /* Sets the region of interest (ROI) for a sensor set or the - vehicle itself. This can then be used by the vehicles control - system to control the vehicle attitude and the attitude of various - devices such as cameras. - |Region of interest mode. (see MAV_ROI enum)| Waypoint index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple cameras etc.)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z| */ - MAV_CMD_DO_LAST=240, /* NOP - This command is only used to mark the upper limit of the DO commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_PREFLIGHT_CALIBRATION=241, /* Trigger calibration. This command will be only accepted if in pre-flight mode. |Gyro calibration: 0: no, 1: yes| Magnetometer calibration: 0: no, 1: yes| Ground pressure: 0: no, 1: yes| Radio calibration: 0: no, 1: yes| Empty| Empty| Empty| */ - MAV_CMD_PREFLIGHT_STORAGE=245, /* Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode. |Parameter storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM| Mission storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM| Reserved| Reserved| Empty| Empty| Empty| */ - MAV_CMD_ENUM_END=246, /* | */ -}; -#endif - /** @brief Data stream IDs. A data stream is not a fixed set of messages, but rather a recommendation to the autopilot software. Individual autopilots may or may not obey the recommended messages. diff --git a/libraries/GCS_MAVLink/include/mavlink/v0.9/common/version.h b/libraries/GCS_MAVLink/include/mavlink/v0.9/common/version.h index 5ca3dc8ca3f75f3194c97689458105b76ccde82f..872c25a677f7a7e95ee4e1af784ad3677b464e2c 100644 --- a/libraries/GCS_MAVLink/include/mavlink/v0.9/common/version.h +++ b/libraries/GCS_MAVLink/include/mavlink/v0.9/common/version.h @@ -5,7 +5,7 @@ #ifndef MAVLINK_VERSION_H #define MAVLINK_VERSION_H -#define MAVLINK_BUILD_DATE "Fri Apr 20 12:22:54 2012" +#define MAVLINK_BUILD_DATE "Tue Apr 24 10:29:51 2012" #define MAVLINK_WIRE_PROTOCOL_VERSION "0.9" #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 101 diff --git a/libraries/GCS_MAVLink/include/mavlink/v0.9/mavlink_helpers.h b/libraries/GCS_MAVLink/include/mavlink/v0.9/mavlink_helpers.h index 98250e1ac8377d4ffaf8966c9165a62fab64cf5f..804490add20dc0f42ac610f1e73c65e0916deb8a 100644 --- a/libraries/GCS_MAVLink/include/mavlink/v0.9/mavlink_helpers.h +++ b/libraries/GCS_MAVLink/include/mavlink/v0.9/mavlink_helpers.h @@ -18,6 +18,24 @@ MAVLINK_HELPER mavlink_status_t* mavlink_get_channel_status(uint8_t chan) return &m_mavlink_status[chan]; } +/* + internal function to give access to the channel buffer for each channel + */ +MAVLINK_HELPER mavlink_message_t* mavlink_get_channel_buffer(uint8_t chan) +{ + +#if MAVLINK_EXTERNAL_RX_BUFFER + // No m_mavlink_message array defined in function, + // has to be defined externally +#ifndef m_mavlink_message +#error ERROR: IF #define MAVLINK_EXTERNAL_RX_BUFFER IS SET, THE BUFFER HAS TO BE ALLOCATED OUTSIDE OF THIS FUNCTION (mavlink_message_t m_mavlink_buffer[MAVLINK_COMM_NUM_BUFFERS];) +#endif +#else + static mavlink_message_t m_mavlink_buffer[MAVLINK_COMM_NUM_BUFFERS]; +#endif + return &m_mavlink_buffer[chan]; +} + /** * @brief Finalize a MAVLink message with channel assignment * @@ -120,7 +138,7 @@ MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint */ MAVLINK_HELPER uint16_t mavlink_msg_to_send_buffer(uint8_t *buffer, const mavlink_message_t *msg) { - memcpy(buffer, (uint8_t *)&msg->magic, MAVLINK_NUM_NON_PAYLOAD_BYTES + (uint16_t)msg->len); + memcpy(buffer, (const uint8_t *)&msg->magic, MAVLINK_NUM_NON_PAYLOAD_BYTES + (uint16_t)msg->len); return MAVLINK_NUM_NON_PAYLOAD_BYTES + (uint16_t)msg->len; } @@ -182,8 +200,6 @@ MAVLINK_HELPER void mavlink_update_checksum(mavlink_message_t* msg, uint8_t c) */ MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_message_t* r_message, mavlink_status_t* r_mavlink_status) { - static mavlink_message_t m_mavlink_message[MAVLINK_COMM_NUM_BUFFERS]; - /* default message crc function. You can override this per-system to put this data in a different memory segment @@ -195,7 +211,7 @@ MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_messa #endif #endif - mavlink_message_t* rxmsg = &m_mavlink_message[chan]; ///< The currently decoded message + mavlink_message_t* rxmsg = mavlink_get_channel_buffer(chan); ///< The currently decoded message mavlink_status_t* status = mavlink_get_channel_status(chan); ///< The current decode status int bufferIndex = 0; @@ -209,14 +225,15 @@ MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_messa { status->parse_state = MAVLINK_PARSE_STATE_GOT_STX; rxmsg->len = 0; + rxmsg->magic = c; mavlink_start_checksum(rxmsg); } break; case MAVLINK_PARSE_STATE_GOT_STX: if (status->msg_received - /* Support shorter buffers than the - default maximum packet size */ +/* Support shorter buffers than the + default maximum packet size */ #if (MAVLINK_MAX_PAYLOAD_LEN < 255) || c > MAVLINK_MAX_PAYLOAD_LEN #endif @@ -269,7 +286,7 @@ MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_messa break; case MAVLINK_PARSE_STATE_GOT_MSGID: - _MAV_PAYLOAD(rxmsg)[status->packet_idx++] = (char)c; + _MAV_PAYLOAD_NON_CONST(rxmsg)[status->packet_idx++] = (char)c; mavlink_update_checksum(rxmsg, c); if (status->packet_idx == rxmsg->len) { @@ -296,6 +313,7 @@ MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_messa else { status->parse_state = MAVLINK_PARSE_STATE_GOT_CRC1; + _MAV_PAYLOAD_NON_CONST(rxmsg)[status->packet_idx] = (char)c; } break; @@ -317,6 +335,7 @@ MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_messa // Successfully got message status->msg_received = 1; status->parse_state = MAVLINK_PARSE_STATE_IDLE; + _MAV_PAYLOAD_NON_CONST(rxmsg)[status->packet_idx+1] = (char)c; memcpy(r_message, rxmsg, sizeof(mavlink_message_t)); } break; diff --git a/libraries/GCS_MAVLink/include/mavlink/v0.9/mavlink_types.h b/libraries/GCS_MAVLink/include/mavlink/v0.9/mavlink_types.h index 630cb84b77ba6d9fa11680edb7bccbf1b249e36f..9d04155c77fdeaa3699371aa502aad23342af657 100644 --- a/libraries/GCS_MAVLink/include/mavlink/v0.9/mavlink_types.h +++ b/libraries/GCS_MAVLink/include/mavlink/v0.9/mavlink_types.h @@ -180,11 +180,26 @@ enum MAVLINK_DATA_STREAM_TYPE #define MAVLINK_MAX_PACKET_LEN (MAVLINK_MAX_PAYLOAD_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES) ///< Maximum packet length +#define MAVLINK_MSG_ID_EXTENDED_MESSAGE 255 +#define MAVLINK_EXTENDED_HEADER_LEN 14 + +#if (defined _MSC_VER) | ((defined __APPLE__) & (defined __MACH__)) | (defined __linux__) + /* full fledged 32bit++ OS */ + #define MAVLINK_MAX_EXTENDED_PACKET_LEN 65507 +#else + /* small microcontrollers */ + #define MAVLINK_MAX_EXTENDED_PACKET_LEN 2048 +#endif + +#define MAVLINK_MAX_EXTENDED_PAYLOAD_LEN (MAVLINK_MAX_EXTENDED_PACKET_LEN - MAVLINK_EXTENDED_HEADER_LEN - MAVLINK_NUM_NON_PAYLOAD_BYTES) + typedef struct param_union { union { float param_float; int32_t param_int32; uint32_t param_uint32; + uint8_t param_uint8; + uint8_t bytes[4]; }; uint8_t type; } mavlink_param_union_t; @@ -209,6 +224,14 @@ typedef struct __mavlink_message { uint64_t payload64[(MAVLINK_MAX_PAYLOAD_LEN+MAVLINK_NUM_CHECKSUM_BYTES+7)/8]; } mavlink_message_t; + +typedef struct __mavlink_extended_message { + mavlink_message_t base_msg; + int32_t extended_payload_len; ///< Length of extended payload if any + uint8_t extended_payload[MAVLINK_MAX_EXTENDED_PAYLOAD_LEN]; +} mavlink_extended_message_t; + + typedef enum { MAVLINK_TYPE_CHAR = 0, MAVLINK_TYPE_UINT8_T = 1, @@ -229,9 +252,9 @@ typedef struct __mavlink_field_info { const char *name; // name of this field const char *print_format; // printing format hint, or NULL mavlink_message_type_t type; // type of this field - unsigned array_length; // if non-zero, field is an array - unsigned wire_offset; // offset of each field in the payload - unsigned structure_offset; // offset in a C structure + unsigned int array_length; // if non-zero, field is an array + unsigned int wire_offset; // offset of each field in the payload + unsigned int structure_offset; // offset in a C structure } mavlink_field_info_t; // note that in this structure the order of fields is the order @@ -242,12 +265,12 @@ typedef struct __mavlink_message_info { mavlink_field_info_t fields[MAVLINK_MAX_FIELDS]; // field information } mavlink_message_info_t; -#define _MAV_PAYLOAD(msg) ((char *)(&(msg)->payload64[0])) +#define _MAV_PAYLOAD(msg) ((const char *)(&((msg)->payload64[0]))) #define _MAV_PAYLOAD_NON_CONST(msg) ((char *)(&((msg)->payload64[0]))) // checksum is immediately after the payload bytes -#define mavlink_ck_a(msg) *(msg->len + (uint8_t *)_MAV_PAYLOAD(msg)) -#define mavlink_ck_b(msg) *((msg->len+(uint16_t)1) + (uint8_t *)_MAV_PAYLOAD(msg)) +#define mavlink_ck_a(msg) *((msg)->len + (uint8_t *)_MAV_PAYLOAD_NON_CONST(msg)) +#define mavlink_ck_b(msg) *(((msg)->len+(uint16_t)1) + (uint8_t *)_MAV_PAYLOAD_NON_CONST(msg)) typedef enum { MAVLINK_COMM_0, diff --git a/libraries/GCS_MAVLink/include/mavlink/v0.9/protocol.h b/libraries/GCS_MAVLink/include/mavlink/v0.9/protocol.h index 05195c36919d04a5bf50c9799ee724af011a20f0..7b3e3c0bd2112c9516e694b729cbc990d2e766bc 100644 --- a/libraries/GCS_MAVLink/include/mavlink/v0.9/protocol.h +++ b/libraries/GCS_MAVLink/include/mavlink/v0.9/protocol.h @@ -155,7 +155,7 @@ static inline void byte_copy_8(char *dst, const char *src) /* like memcpy(), but if src is NULL, do a memset to zero - */ +*/ static void mav_array_memcpy(void *dest, const void *src, size_t n) { if (src == NULL) { @@ -171,6 +171,7 @@ static void mav_array_memcpy(void *dest, const void *src, size_t n) static inline void _mav_put_char_array(char *buf, uint8_t wire_offset, const char *b, uint8_t array_length) { mav_array_memcpy(&buf[wire_offset], b, array_length); + } /* @@ -179,6 +180,7 @@ static inline void _mav_put_char_array(char *buf, uint8_t wire_offset, const cha static inline void _mav_put_uint8_t_array(char *buf, uint8_t wire_offset, const uint8_t *b, uint8_t array_length) { mav_array_memcpy(&buf[wire_offset], b, array_length); + } /* @@ -187,6 +189,7 @@ static inline void _mav_put_uint8_t_array(char *buf, uint8_t wire_offset, const static inline void _mav_put_int8_t_array(char *buf, uint8_t wire_offset, const int8_t *b, uint8_t array_length) { mav_array_memcpy(&buf[wire_offset], b, array_length); + } #if MAVLINK_NEED_BYTE_SWAP @@ -206,7 +209,7 @@ static inline void _mav_put_ ## TYPE ##_array(char *buf, uint8_t wire_offset, co #define _MAV_PUT_ARRAY(TYPE, V) \ static inline void _mav_put_ ## TYPE ##_array(char *buf, uint8_t wire_offset, const TYPE *b, uint8_t array_length) \ { \ - mav_array_memcpy(&buf[wire_offset], b, array_length*sizeof(TYPE)); \ + mav_array_memcpy(&buf[wire_offset], b, array_length*sizeof(TYPE)); \ } #endif @@ -219,9 +222,9 @@ _MAV_PUT_ARRAY(int64_t, i64) _MAV_PUT_ARRAY(float, f) _MAV_PUT_ARRAY(double, d) -#define _MAV_RETURN_char(msg, wire_offset) _MAV_PAYLOAD(msg)[wire_offset] -#define _MAV_RETURN_int8_t(msg, wire_offset) (int8_t)_MAV_PAYLOAD(msg)[wire_offset] -#define _MAV_RETURN_uint8_t(msg, wire_offset) (uint8_t)_MAV_PAYLOAD(msg)[wire_offset] +#define _MAV_RETURN_char(msg, wire_offset) (const char)_MAV_PAYLOAD(msg)[wire_offset] +#define _MAV_RETURN_int8_t(msg, wire_offset) (const int8_t)_MAV_PAYLOAD(msg)[wire_offset] +#define _MAV_RETURN_uint8_t(msg, wire_offset) (const uint8_t)_MAV_PAYLOAD(msg)[wire_offset] #if MAVLINK_NEED_BYTE_SWAP #define _MAV_MSG_RETURN_TYPE(TYPE, SIZE) \ diff --git a/libraries/GCS_MAVLink/include/mavlink/v1.0/ardupilotmega/version.h b/libraries/GCS_MAVLink/include/mavlink/v1.0/ardupilotmega/version.h index 7cc3ee13d9727a407171b783fe8532bf79600cf8..2f6014644e392a533c7db1fdc144a0532f23b1a9 100644 --- a/libraries/GCS_MAVLink/include/mavlink/v1.0/ardupilotmega/version.h +++ b/libraries/GCS_MAVLink/include/mavlink/v1.0/ardupilotmega/version.h @@ -5,7 +5,7 @@ #ifndef MAVLINK_VERSION_H #define MAVLINK_VERSION_H -#define MAVLINK_BUILD_DATE "Fri Apr 20 12:22:47 2012" +#define MAVLINK_BUILD_DATE "Tue Apr 24 10:29:51 2012" #define MAVLINK_WIRE_PROTOCOL_VERSION "1.0" #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 101 diff --git a/libraries/GCS_MAVLink/include/mavlink/v1.0/common/common.h b/libraries/GCS_MAVLink/include/mavlink/v1.0/common/common.h index 9a76edeaadba94ce754855ad0fccc6c69edd5414..d9851110d346644a59fd64087f5e85683fcb985f 100644 --- a/libraries/GCS_MAVLink/include/mavlink/v1.0/common/common.h +++ b/libraries/GCS_MAVLink/include/mavlink/v1.0/common/common.h @@ -239,48 +239,6 @@ enum MAVLINK_DATA_STREAM_TYPE }; #endif -/** @brief Commands to be executed by the MAV. They can be executed on user request, or as part of a mission script. If the action is used in a mission, the parameter mapping to the waypoint/mission message is as follows: Param 1, Param 2, Param 3, Param 4, X: Param 5, Y:Param 6, Z:Param 7. This command list is similar what ARINC 424 is for commercial aircraft: A data format how to interpret waypoint/mission data. */ -#ifndef HAVE_ENUM_MAV_CMD -#define HAVE_ENUM_MAV_CMD -enum MAV_CMD -{ - MAV_CMD_NAV_WAYPOINT=16, /* Navigate to MISSION. |Hold time in decimal seconds. (ignored by fixed wing, time to stay at MISSION for rotary wing)| Acceptance radius in meters (if the sphere with this radius is hit, the MISSION counts as reached)| 0 to pass through the WP, if > 0 radius in meters to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control.| Desired yaw angle at MISSION (rotary wing)| Latitude| Longitude| Altitude| */ - MAV_CMD_NAV_LOITER_UNLIM=17, /* Loiter around this MISSION an unlimited amount of time |Empty| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */ - MAV_CMD_NAV_LOITER_TURNS=18, /* Loiter around this MISSION for X turns |Turns| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */ - MAV_CMD_NAV_LOITER_TIME=19, /* Loiter around this MISSION for X seconds |Seconds (decimal)| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */ - MAV_CMD_NAV_RETURN_TO_LAUNCH=20, /* Return to launch location |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_NAV_LAND=21, /* Land at location |Empty| Empty| Empty| Desired yaw angle.| Latitude| Longitude| Altitude| */ - MAV_CMD_NAV_TAKEOFF=22, /* Takeoff from ground / hand |Minimum pitch (if airspeed sensor present), desired pitch without sensor| Empty| Empty| Yaw angle (if magnetometer present), ignored without magnetometer| Latitude| Longitude| Altitude| */ - MAV_CMD_NAV_ROI=80, /* Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Region of intereset mode. (see MAV_ROI enum)| MISSION index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple ROI's)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z| */ - MAV_CMD_NAV_PATHPLANNING=81, /* Control autonomous path planning on the MAV. |0: Disable local obstacle avoidance / local path planning (without resetting map), 1: Enable local path planning, 2: Enable and reset local path planning| 0: Disable full path planning (without resetting map), 1: Enable, 2: Enable and reset map/occupancy grid, 3: Enable and reset planned route, but not occupancy grid| Empty| Yaw angle at goal, in compass degrees, [0..360]| Latitude/X of goal| Longitude/Y of goal| Altitude/Z of goal| */ - MAV_CMD_NAV_LAST=95, /* NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_CONDITION_DELAY=112, /* Delay mission state machine. |Delay in seconds (decimal)| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_CONDITION_CHANGE_ALT=113, /* Ascend/descend at rate. Delay mission state machine until desired altitude reached. |Descent / Ascend rate (m/s)| Empty| Empty| Empty| Empty| Empty| Finish Altitude| */ - MAV_CMD_CONDITION_DISTANCE=114, /* Delay mission state machine until within desired distance of next NAV point. |Distance (meters)| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_CONDITION_YAW=115, /* Reach a certain target angle. |target angle: [0-360], 0 is north| speed during yaw change:[deg per second]| direction: negative: counter clockwise, positive: clockwise [-1,1]| relative offset or absolute angle: [ 1,0]| Empty| Empty| Empty| */ - MAV_CMD_CONDITION_LAST=159, /* NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_SET_MODE=176, /* Set system mode. |Mode, as defined by ENUM MAV_MODE| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_JUMP=177, /* Jump to the desired command in the mission list. Repeat this action only the specified number of times |Sequence number| Repeat count| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_CHANGE_SPEED=178, /* Change speed and/or throttle set points. |Speed type (0=Airspeed, 1=Ground Speed)| Speed (m/s, -1 indicates no change)| Throttle ( Percent, -1 indicates no change)| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_SET_HOME=179, /* Changes the home location either to the current location or a specified location. |Use current (1=use current location, 0=use specified location)| Empty| Empty| Empty| Latitude| Longitude| Altitude| */ - MAV_CMD_DO_SET_PARAMETER=180, /* Set a system parameter. Caution! Use of this command requires knowledge of the numeric enumeration value of the parameter. |Parameter number| Parameter value| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_SET_RELAY=181, /* Set a relay to a condition. |Relay number| Setting (1=on, 0=off, others possible depending on system hardware)| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_REPEAT_RELAY=182, /* Cycle a relay on and off for a desired number of cyles with a desired period. |Relay number| Cycle count| Cycle time (seconds, decimal)| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_SET_SERVO=183, /* Set a servo to a desired PWM value. |Servo number| PWM (microseconds, 1000 to 2000 typical)| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_REPEAT_SERVO=184, /* Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period. |Servo number| PWM (microseconds, 1000 to 2000 typical)| Cycle count| Cycle time (seconds)| Empty| Empty| Empty| */ - MAV_CMD_DO_CONTROL_VIDEO=200, /* Control onboard camera system. |Camera ID (-1 for all)| Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw| Transmission mode: 0: video stream, >0: single images every n seconds (decimal)| Recording: 0: disabled, 1: enabled compressed, 2: enabled raw| Empty| Empty| Empty| */ - MAV_CMD_DO_LAST=240, /* NOP - This command is only used to mark the upper limit of the DO commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_PREFLIGHT_CALIBRATION=241, /* Trigger calibration. This command will be only accepted if in pre-flight mode. |Gyro calibration: 0: no, 1: yes| Magnetometer calibration: 0: no, 1: yes| Ground pressure: 0: no, 1: yes| Radio calibration: 0: no, 1: yes| Empty| Empty| Empty| */ - MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS=242, /* Set sensor offsets. This command will be only accepted if in pre-flight mode. |Sensor to adjust the offsets for: 0: gyros, 1: accelerometer, 2: magnetometer, 3: barometer, 4: optical flow| X axis offset (or generic dimension 1), in the sensor's raw units| Y axis offset (or generic dimension 2), in the sensor's raw units| Z axis offset (or generic dimension 3), in the sensor's raw units| Generic dimension 4, in the sensor's raw units| Generic dimension 5, in the sensor's raw units| Generic dimension 6, in the sensor's raw units| */ - MAV_CMD_PREFLIGHT_STORAGE=245, /* Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode. |Parameter storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM| Mission storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM| Reserved| Reserved| Empty| Empty| Empty| */ - MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN=246, /* Request the reboot or shutdown of system components. |0: Do nothing for autopilot, 1: Reboot autopilot, 2: Shutdown autopilot.| 0: Do nothing for onboard computer, 1: Reboot onboard computer, 2: Shutdown onboard computer.| Reserved| Reserved| Empty| Empty| Empty| */ - MAV_CMD_OVERRIDE_GOTO=252, /* Hold / continue the current action |MAV_GOTO_DO_HOLD: hold MAV_GOTO_DO_CONTINUE: continue with next item in mission plan| MAV_GOTO_HOLD_AT_CURRENT_POSITION: Hold at current position MAV_GOTO_HOLD_AT_SPECIFIED_POSITION: hold at specified position| MAV_FRAME coordinate frame of hold point| Desired yaw angle in degrees| Latitude / X position| Longitude / Y position| Altitude / Z position| */ - MAV_CMD_MISSION_START=300, /* start running a mission |first_item: the first mission item to run| last_item: the last mission item to run (after this item is run, the mission ends)| */ - MAV_CMD_COMPONENT_ARM_DISARM=400, /* Arms / Disarms a component |1 to arm, 0 to disarm| */ - MAV_CMD_ENUM_END=401, /* | */ -}; -#endif - /** @brief Data stream IDs. A data stream is not a fixed set of messages, but rather a recommendation to the autopilot software. Individual autopilots may or may not obey the recommended messages. */ diff --git a/libraries/GCS_MAVLink/include/mavlink/v1.0/common/version.h b/libraries/GCS_MAVLink/include/mavlink/v1.0/common/version.h index 0e49f8232ed82b3812bc519d72af4fe90af494bd..3cd0335edd3b799fc528ac95b04268f8060d17b1 100644 --- a/libraries/GCS_MAVLink/include/mavlink/v1.0/common/version.h +++ b/libraries/GCS_MAVLink/include/mavlink/v1.0/common/version.h @@ -5,7 +5,7 @@ #ifndef MAVLINK_VERSION_H #define MAVLINK_VERSION_H -#define MAVLINK_BUILD_DATE "Fri Apr 20 12:22:54 2012" +#define MAVLINK_BUILD_DATE "Tue Apr 24 10:29:51 2012" #define MAVLINK_WIRE_PROTOCOL_VERSION "1.0" #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 101 diff --git a/libraries/GCS_MAVLink/message_definitions/ardupilotmega.xml b/libraries/GCS_MAVLink/message_definitions/ardupilotmega.xml new file mode 100644 index 0000000000000000000000000000000000000000..618b9bc24c347a2ce65c3e199c31c6bb6e1784e6 --- /dev/null +++ b/libraries/GCS_MAVLink/message_definitions/ardupilotmega.xml @@ -0,0 +1,270 @@ +<?xml version='1.0'?> +<mavlink> + <include>common.xml</include> + <!-- note that APM specific messages should use the command id + range from 150 to 250, to leave plenty of room for growth + of common.xml + + If you prototype a message here, then you should consider if it + is general enough to move into common.xml later + --> + + + <enums> + <!-- Camera Mount mode Enumeration --> + <enum name="MAV_MOUNT_MODE"> + <description>Enumeration of possible mount operation modes</description> + <entry name="MAV_MOUNT_MODE_RETRACT" value="0"><description>Load and keep safe position (Roll,Pitch,Yaw) from EEPROM and stop stabilization</description></entry> + <entry name="MAV_MOUNT_MODE_NEUTRAL" value="1"><description>Load and keep neutral position (Roll,Pitch,Yaw) from EEPROM.</description></entry> + <entry name="MAV_MOUNT_MODE_MAVLINK_TARGETING" value="2"><description>Load neutral position and start MAVLink Roll,Pitch,Yaw control with stabilization</description></entry> + <entry name="MAV_MOUNT_MODE_RC_TARGETING" value="3"><description>Load neutral position and start RC Roll,Pitch,Yaw control with stabilization</description></entry> + <entry name="MAV_MOUNT_MODE_GPS_POINT" value="4"><description>Load neutral position and start to point to Lat,Lon,Alt</description></entry> + </enum> + + <enum name="MAV_CMD" > + <!-- Camera Controller Mission Commands Enumeration --> + <entry name="MAV_CMD_DO_DIGICAM_CONFIGURE" value="202"> + <description>Mission command to configure an on-board camera controller system.</description> + <param index="1">Modes: P, TV, AV, M, Etc</param> + <param index="2">Shutter speed: Divisor number for one second</param> + <param index="3">Aperture: F stop number</param> + <param index="4">ISO number e.g. 80, 100, 200, Etc</param> + <param index="5">Exposure type enumerator</param> + <param index="6">Command Identity</param> + <param index="7">Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off)</param> + </entry> + + <entry name="MAV_CMD_DO_DIGICAM_CONTROL" value="203"> + <description>Mission command to control an on-board camera controller system.</description> + <param index="1">Session control e.g. show/hide lens</param> + <param index="2">Zoom's absolute position</param> + <param index="3">Zooming step value to offset zoom from the current position</param> + <param index="4">Focus Locking, Unlocking or Re-locking</param> + <param index="5">Shooting Command</param> + <param index="6">Command Identity</param> + <param index="7">Empty</param> + </entry> + + <!-- Camera Mount Mission Commands Enumeration --> + <entry name="MAV_CMD_DO_MOUNT_CONFIGURE" value="204"> + <description>Mission command to configure a camera or antenna mount</description> + <param index="1">Mount operation mode (see MAV_MOUNT_MODE enum)</param> + <param index="2">stabilize roll? (1 = yes, 0 = no)</param> + <param index="3">stabilize pitch? (1 = yes, 0 = no)</param> + <param index="4">stabilize yaw? (1 = yes, 0 = no)</param> + <param index="5">Empty</param> + <param index="6">Empty</param> + <param index="7">Empty</param> + </entry> + + <entry name="MAV_CMD_DO_MOUNT_CONTROL" value="205"> + <description>Mission command to control a camera or antenna mount</description> + <param index="1">pitch(deg*100) or lat, depending on mount mode.</param> + <param index="2">roll(deg*100) or lon depending on mount mode</param> + <param index="3">yaw(deg*100) or alt (in cm) depending on mount mode</param> + <param index="4">Empty</param> + <param index="5">Empty</param> + <param index="6">Empty</param> + <param index="7">Empty</param> + </entry> + </enum> + + <!-- fenced mode enums --> + <enum name="FENCE_ACTION"> + <entry name="FENCE_ACTION_NONE" value="0"> + <description>Disable fenced mode</description> + </entry> + <entry name="FENCE_ACTION_GUIDED" value="1"> + <description>Switched to guided mode to return point (fence point 0)</description> + </entry> + </enum> + + <enum name="FENCE_BREACH"> + <entry name="FENCE_BREACH_NONE" value="0"> + <description>No last fence breach</description> + </entry> + <entry name="FENCE_BREACH_MINALT" value="1"> + <description>Breached minimum altitude</description> + </entry> + <entry name="FENCE_BREACH_MAXALT" value="2"> + <description>Breached minimum altitude</description> + </entry> + <entry name="FENCE_BREACH_BOUNDARY" value="3"> + <description>Breached fence boundary</description> + </entry> + </enum> + </enums> + + <messages> + <message id="150" name="SENSOR_OFFSETS"> + <description>Offsets and calibrations values for hardware + sensors. This makes it easier to debug the calibration process.</description> + <field type="int16_t" name="mag_ofs_x">magnetometer X offset</field> + <field type="int16_t" name="mag_ofs_y">magnetometer Y offset</field> + <field type="int16_t" name="mag_ofs_z">magnetometer Z offset</field> + <field type="float" name="mag_declination">magnetic declination (radians)</field> + <field type="int32_t" name="raw_press">raw pressure from barometer</field> + <field type="int32_t" name="raw_temp">raw temperature from barometer</field> + <field type="float" name="gyro_cal_x">gyro X calibration</field> + <field type="float" name="gyro_cal_y">gyro Y calibration</field> + <field type="float" name="gyro_cal_z">gyro Z calibration</field> + <field type="float" name="accel_cal_x">accel X calibration</field> + <field type="float" name="accel_cal_y">accel Y calibration</field> + <field type="float" name="accel_cal_z">accel Z calibration</field> + </message> + + <message id="151" name="SET_MAG_OFFSETS"> + <description>set the magnetometer offsets</description> + <field type="uint8_t" name="target_system">System ID</field> + <field type="uint8_t" name="target_component">Component ID</field> + <field type="int16_t" name="mag_ofs_x">magnetometer X offset</field> + <field type="int16_t" name="mag_ofs_y">magnetometer Y offset</field> + <field type="int16_t" name="mag_ofs_z">magnetometer Z offset</field> + </message> + + <message id="152" name="MEMINFO"> + <description>state of APM memory</description> + <field type="uint16_t" name="brkval">heap top</field> + <field type="uint16_t" name="freemem">free memory</field> + </message> + + <message id="153" name="AP_ADC"> + <description>raw ADC output</description> + <field type="uint16_t" name="adc1">ADC output 1</field> + <field type="uint16_t" name="adc2">ADC output 2</field> + <field type="uint16_t" name="adc3">ADC output 3</field> + <field type="uint16_t" name="adc4">ADC output 4</field> + <field type="uint16_t" name="adc5">ADC output 5</field> + <field type="uint16_t" name="adc6">ADC output 6</field> + </message> + + <!-- Camera Controller Messages --> + <message name="DIGICAM_CONFIGURE" id="154"> + <description>Configure on-board Camera Control System.</description> + <field name="target_system" type="uint8_t">System ID</field> + <field name="target_component" type="uint8_t">Component ID</field> + <field name="mode" type="uint8_t">Mode enumeration from 1 to N //P, TV, AV, M, Etc (0 means ignore)</field> + <field name="shutter_speed" type="uint16_t">Divisor number //e.g. 1000 means 1/1000 (0 means ignore)</field> + <field name="aperture" type="uint8_t">F stop number x 10 //e.g. 28 means 2.8 (0 means ignore)</field> + <field name="iso" type="uint8_t">ISO enumeration from 1 to N //e.g. 80, 100, 200, Etc (0 means ignore)</field> + <field name="exposure_type" type="uint8_t">Exposure type enumeration from 1 to N (0 means ignore)</field> + <field name="command_id" type="uint8_t">Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once</field> + <field name="engine_cut_off" type="uint8_t">Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off)</field> + <field name="extra_param" type="uint8_t">Extra parameters enumeration (0 means ignore)</field> + <field name="extra_value" type="float">Correspondent value to given extra_param</field> + </message> + + <message name="DIGICAM_CONTROL" id="155"> + <description>Control on-board Camera Control System to take shots.</description> + <field name="target_system" type="uint8_t">System ID</field> + <field name="target_component" type="uint8_t">Component ID</field> + <field name="session" type="uint8_t">0: stop, 1: start or keep it up //Session control e.g. show/hide lens</field> + <field name="zoom_pos" type="uint8_t">1 to N //Zoom's absolute position (0 means ignore)</field> + <field name="zoom_step" type="int8_t">-100 to 100 //Zooming step value to offset zoom from the current position</field> + <field name="focus_lock" type="uint8_t">0: unlock focus or keep unlocked, 1: lock focus or keep locked, 3: re-lock focus</field> + <field name="shot" type="uint8_t">0: ignore, 1: shot or start filming</field> + <field name="command_id" type="uint8_t">Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once</field> + <field name="extra_param" type="uint8_t">Extra parameters enumeration (0 means ignore)</field> + <field name="extra_value" type="float">Correspondent value to given extra_param</field> + </message> + + <!-- Camera Mount Messages --> + <message name="MOUNT_CONFIGURE" id="156"> + <description>Message to configure a camera mount, directional antenna, etc.</description> + <field name="target_system" type="uint8_t">System ID</field> + <field name="target_component" type="uint8_t">Component ID</field> + <field name="mount_mode" type="uint8_t">mount operating mode (see MAV_MOUNT_MODE enum)</field> + <field name="stab_roll" type="uint8_t">(1 = yes, 0 = no)</field> + <field name="stab_pitch" type="uint8_t">(1 = yes, 0 = no)</field> + <field name="stab_yaw" type="uint8_t">(1 = yes, 0 = no)</field> + </message> + + <message name="MOUNT_CONTROL" id="157"> + <description>Message to control a camera mount, directional antenna, etc.</description> + <field name="target_system" type="uint8_t">System ID</field> + <field name="target_component" type="uint8_t">Component ID</field> + <field name="input_a" type="int32_t">pitch(deg*100) or lat, depending on mount mode</field> + <field name="input_b" type="int32_t">roll(deg*100) or lon depending on mount mode</field> + <field name="input_c" type="int32_t">yaw(deg*100) or alt (in cm) depending on mount mode</field> + <field name="save_position" type="uint8_t">if "1" it will save current trimmed position on EEPROM (just valid for NEUTRAL and LANDING)</field> + </message> + + <message name="MOUNT_STATUS" id="158"> + <description>Message with some status from APM to GCS about camera or antenna mount</description> + <field name="target_system" type="uint8_t">System ID</field> + <field name="target_component" type="uint8_t">Component ID</field> + <field name="pointing_a" type="int32_t">pitch(deg*100) or lat, depending on mount mode</field> + <field name="pointing_b" type="int32_t">roll(deg*100) or lon depending on mount mode</field> + <field name="pointing_c" type="int32_t">yaw(deg*100) or alt (in cm) depending on mount mode</field> + </message> + + <!-- geo-fence messages --> + <message name="FENCE_POINT" id="160"> + <description>A fence point. Used to set a point when from + GCS -> MAV. Also used to return a point from MAV -> GCS</description> + <field name="target_system" type="uint8_t">System ID</field> + <field name="target_component" type="uint8_t">Component ID</field> + <field name="idx" type="uint8_t">point index (first point is 1, 0 is for return point)</field> + <field name="count" type="uint8_t">total number of points (for sanity checking)</field> + <field name="lat" type="float">Latitude of point</field> + <field name="lng" type="float">Longitude of point</field> + </message> + + <message name="FENCE_FETCH_POINT" id="161"> + <description>Request a current fence point from MAV</description> + <field name="target_system" type="uint8_t">System ID</field> + <field name="target_component" type="uint8_t">Component ID</field> + <field name="idx" type="uint8_t">point index (first point is 1, 0 is for return point)</field> + </message> + + <message name="FENCE_STATUS" id="162"> + <description>Status of geo-fencing. Sent in extended + status stream when fencing enabled</description> + <field name="breach_status" type="uint8_t">0 if currently inside fence, 1 if outside</field> + <field name="breach_count" type="uint16_t">number of fence breaches</field> + <field name="breach_type" type="uint8_t">last breach type (see FENCE_BREACH_* enum)</field> + <field name="breach_time" type="uint32_t">time of last breach in milliseconds since boot</field> + </message> + + <message name="AHRS" id="163"> + <description>Status of DCM attitude estimator</description> + <field type="float" name="omegaIx">X gyro drift estimate rad/s</field> + <field type="float" name="omegaIy">Y gyro drift estimate rad/s</field> + <field type="float" name="omegaIz">Z gyro drift estimate rad/s</field> + <field type="float" name="accel_weight">average accel_weight</field> + <field type="float" name="renorm_val">average renormalisation value</field> + <field type="float" name="error_rp">average error_roll_pitch value</field> + <field type="float" name="error_yaw">average error_yaw value</field> + </message> + + <message name="SIMSTATE" id="164"> + <description>Status of simulation environment, if used</description> + <field type="float" name="roll">Roll angle (rad)</field> + <field type="float" name="pitch">Pitch angle (rad)</field> + <field type="float" name="yaw">Yaw angle (rad)</field> + <field type="float" name="xacc">X acceleration m/s/s</field> + <field type="float" name="yacc">Y acceleration m/s/s</field> + <field type="float" name="zacc">Z acceleration m/s/s</field> + <field type="float" name="xgyro">Angular speed around X axis rad/s</field> + <field type="float" name="ygyro">Angular speed around Y axis rad/s</field> + <field type="float" name="zgyro">Angular speed around Z axis rad/s</field> + </message> + + <message name="HWSTATUS" id="165"> + <description>Status of key hardware</description> + <field type="uint16_t" name="Vcc">board voltage (mV)</field> + <field type="uint8_t" name="I2Cerr">I2C error count</field> + </message> + + <message name="RADIO" id="166"> + <description>Status generated by radio</description> + <field type="uint8_t" name="rssi">local signal strength</field> + <field type="uint8_t" name="remrssi">remote signal strength</field> + <field type="uint8_t" name="txbuf">how full the tx buffer is as a percentage</field> + <field type="uint8_t" name="noise">background noise level</field> + <field type="uint8_t" name="remnoise">remote background noise level</field> + <field type="uint16_t" name="rxerrors">receive errors</field> + <field type="uint16_t" name="fixed">count of error corrected packets</field> + </message> + </messages> +</mavlink> diff --git a/libraries/GCS_MAVLink/message_definitions/common.xml b/libraries/GCS_MAVLink/message_definitions/common.xml new file mode 100644 index 0000000000000000000000000000000000000000..dd4ea84430da5a7ceed5ae92bdfaaff54621d75c --- /dev/null +++ b/libraries/GCS_MAVLink/message_definitions/common.xml @@ -0,0 +1,941 @@ +<?xml version='1.0'?> +<mavlink> + <version>2</version> + <enums> + <enum name="MAV_CMD"> + <description>Commands to be executed by the MAV. They can be executed on user request, + or as part of a mission script. If the action is used in a mission, the parameter mapping + to the waypoint/mission message is as follows: + Param 1, Param 2, Param 3, Param 4, X: Param 5, Y:Param 6, Z:Param 7. This command list is similar what + ARINC 424 is for commercial aircraft: A data format how to interpret waypoint/mission data.</description> + <entry value="16" name="MAV_CMD_NAV_WAYPOINT"> + <description>Navigate to waypoint.</description> + <param index="1">Hold time in decimal seconds. (ignored by fixed wing, time to stay at waypoint for rotary wing)</param> + <param index="2">Acceptance radius in meters (if the sphere with this radius is hit, the waypoint counts as reached)</param> + <param index="3">0 to pass through the WP, if > 0 radius in meters to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control.</param> + <param index="4">Desired yaw angle at waypoint (rotary wing)</param> + <param index="5">Latitude</param> + <param index="6">Longitude</param> + <param index="7">Altitude</param> + </entry> + <entry value="17" name="MAV_CMD_NAV_LOITER_UNLIM"> + <description>Loiter around this waypoint an unlimited amount of time</description> + <param index="1">Empty</param> + <param index="2">Empty</param> + <param index="3">Radius around waypoint, in meters. If positive loiter clockwise, else counter-clockwise</param> + <param index="4">Desired yaw angle.</param> + <param index="5">Latitude</param> + <param index="6">Longitude</param> + <param index="7">Altitude</param> + </entry> + <entry value="18" name="MAV_CMD_NAV_LOITER_TURNS"> + <description>Loiter around this waypoint for X turns</description> + <param index="1">Turns</param> + <param index="2">Empty</param> + <param index="3">Radius around waypoint, in meters. If positive loiter clockwise, else counter-clockwise</param> + <param index="4">Desired yaw angle.</param> + <param index="5">Latitude</param> + <param index="6">Longitude</param> + <param index="7">Altitude</param> + </entry> + <entry value="19" name="MAV_CMD_NAV_LOITER_TIME"> + <description>Loiter around this waypoint for X seconds</description> + <param index="1">Seconds (decimal)</param> + <param index="2">Empty</param> + <param index="3">Radius around waypoint, in meters. If positive loiter clockwise, else counter-clockwise</param> + <param index="4">Desired yaw angle.</param> + <param index="5">Latitude</param> + <param index="6">Longitude</param> + <param index="7">Altitude</param> + </entry> + <entry value="20" name="MAV_CMD_NAV_RETURN_TO_LAUNCH"> + <description>Return to launch location</description> + <param index="1">Empty</param> + <param index="2">Empty</param> + <param index="3">Empty</param> + <param index="4">Empty</param> + <param index="5">Empty</param> + <param index="6">Empty</param> + <param index="7">Empty</param> + </entry> + <entry value="21" name="MAV_CMD_NAV_LAND"> + <description>Land at location</description> + <param index="1">Empty</param> + <param index="2">Empty</param> + <param index="3">Empty</param> + <param index="4">Desired yaw angle.</param> + <param index="5">Latitude</param> + <param index="6">Longitude</param> + <param index="7">Altitude</param> + </entry> + <entry value="22" name="MAV_CMD_NAV_TAKEOFF"> + <description>Takeoff from ground / hand</description> + <param index="1">Minimum pitch (if airspeed sensor present), desired pitch without sensor</param> + <param index="2">Empty</param> + <param index="3">Empty</param> + <param index="4">Yaw angle (if magnetometer present), ignored without magnetometer</param> + <param index="5">Latitude</param> + <param index="6">Longitude</param> + <param index="7">Altitude</param> + </entry> + <entry value="80" name="MAV_CMD_NAV_ROI"> + <description>Sets the region of interest (ROI) for a sensor set or the + vehicle itself. This can then be used by the vehicles control + system to control the vehicle attitude and the attitude of various + sensors such as cameras.</description> + <param index="1">Region of intereset mode. (see MAV_ROI enum)</param> + <param index="2">Waypoint index/ target ID. (see MAV_ROI enum)</param> + <param index="3">ROI index (allows a vehicle to manage multiple ROI's)</param> + <param index="4">Empty</param> + <param index="5">x the location of the fixed ROI (see MAV_FRAME)</param> + <param index="6">y</param> + <param index="7">z</param> + </entry> + <entry value="81" name="MAV_CMD_NAV_PATHPLANNING"> + <description>Control autonomous path planning on the MAV.</description> + <param index="1">0: Disable local obstacle avoidance / local path planning (without resetting map), 1: Enable local path planning, 2: Enable and reset local path planning</param> + <param index="2">0: Disable full path planning (without resetting map), 1: Enable, 2: Enable and reset map/occupancy grid, 3: Enable and reset planned route, but not occupancy grid</param> + <param index="3">Empty</param> + <param index="4">Yaw angle at goal, in compass degrees, [0..360]</param> + <param index="5">Latitude/X of goal</param> + <param index="6">Longitude/Y of goal</param> + <param index="7">Altitude/Z of goal</param> + </entry> + <entry value="95" name="MAV_CMD_NAV_LAST"> + <description>NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration</description> + <param index="1">Empty</param> + <param index="2">Empty</param> + <param index="3">Empty</param> + <param index="4">Empty</param> + <param index="5">Empty</param> + <param index="6">Empty</param> + <param index="7">Empty</param> + </entry> + <entry value="112" name="MAV_CMD_CONDITION_DELAY"> + <description>Delay mission state machine.</description> + <param index="1">Delay in seconds (decimal)</param> + <param index="2">Empty</param> + <param index="3">Empty</param> + <param index="4">Empty</param> + <param index="5">Empty</param> + <param index="6">Empty</param> + <param index="7">Empty</param> + </entry> + <entry value="113" name="MAV_CMD_CONDITION_CHANGE_ALT"> + <description>Ascend/descend at rate. Delay mission state machine until desired altitude reached.</description> + <param index="1">Descent / Ascend rate (m/s)</param> + <param index="2">Empty</param> + <param index="3">Empty</param> + <param index="4">Empty</param> + <param index="5">Empty</param> + <param index="6">Empty</param> + <param index="7">Finish Altitude</param> + </entry> + <entry value="114" name="MAV_CMD_CONDITION_DISTANCE"> + <description>Delay mission state machine until within desired distance of next NAV point.</description> + <param index="1">Distance (meters)</param> + <param index="2">Empty</param> + <param index="3">Empty</param> + <param index="4">Empty</param> + <param index="5">Empty</param> + <param index="6">Empty</param> + <param index="7">Empty</param> + </entry> + <entry value="115" name="MAV_CMD_CONDITION_YAW"> + <description>Reach a certain target angle.</description> + <param index="1">target angle: [0-360], 0 is north</param> + <param index="2">speed during yaw change:[deg per second]</param> + <param index="3">direction: negative: counter clockwise, positive: clockwise [-1,1]</param> + <param index="4">relative offset or absolute angle: [ 1,0]</param> + <param index="5">Empty</param> + <param index="6">Empty</param> + <param index="7">Empty</param> + </entry> + <entry value="159" name="MAV_CMD_CONDITION_LAST"> + <description>NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration</description> + <param index="1">Empty</param> + <param index="2">Empty</param> + <param index="3">Empty</param> + <param index="4">Empty</param> + <param index="5">Empty</param> + <param index="6">Empty</param> + <param index="7">Empty</param> + </entry> + <entry value="176" name="MAV_CMD_DO_SET_MODE"> + <description>Set system mode.</description> + <param index="1">Mode, as defined by ENUM MAV_MODE</param> + <param index="2">Empty</param> + <param index="3">Empty</param> + <param index="4">Empty</param> + <param index="5">Empty</param> + <param index="6">Empty</param> + <param index="7">Empty</param> + </entry> + <entry value="177" name="MAV_CMD_DO_JUMP"> + <description>Jump to the desired command in the mission list. Repeat this action only the specified number of times</description> + <param index="1">Sequence number</param> + <param index="2">Repeat count</param> + <param index="3">Empty</param> + <param index="4">Empty</param> + <param index="5">Empty</param> + <param index="6">Empty</param> + <param index="7">Empty</param> + </entry> + <entry value="178" name="MAV_CMD_DO_CHANGE_SPEED"> + <description>Change speed and/or throttle set points.</description> + <param index="1">Speed type (0=Airspeed, 1=Ground Speed)</param> + <param index="2">Speed (m/s, -1 indicates no change)</param> + <param index="3">Throttle ( Percent, -1 indicates no change)</param> + <param index="4">Empty</param> + <param index="5">Empty</param> + <param index="6">Empty</param> + <param index="7">Empty</param> + </entry> + <entry value="179" name="MAV_CMD_DO_SET_HOME"> + <description>Changes the home location either to the current location or a specified location.</description> + <param index="1">Use current (1=use current location, 0=use specified location)</param> + <param index="2">Empty</param> + <param index="3">Empty</param> + <param index="4">Empty</param> + <param index="5">Latitude</param> + <param index="6">Longitude</param> + <param index="7">Altitude</param> + </entry> + <entry value="180" name="MAV_CMD_DO_SET_PARAMETER"> + <description>Set a system parameter. Caution! Use of this command requires knowledge of the numeric enumeration value of the parameter.</description> + <param index="1">Parameter number</param> + <param index="2">Parameter value</param> + <param index="3">Empty</param> + <param index="4">Empty</param> + <param index="5">Empty</param> + <param index="6">Empty</param> + <param index="7">Empty</param> + </entry> + <entry value="181" name="MAV_CMD_DO_SET_RELAY"> + <description>Set a relay to a condition.</description> + <param index="1">Relay number</param> + <param index="2">Setting (1=on, 0=off, others possible depending on system hardware)</param> + <param index="3">Empty</param> + <param index="4">Empty</param> + <param index="5">Empty</param> + <param index="6">Empty</param> + <param index="7">Empty</param> + </entry> + <entry value="182" name="MAV_CMD_DO_REPEAT_RELAY"> + <description>Cycle a relay on and off for a desired number of cyles with a desired period.</description> + <param index="1">Relay number</param> + <param index="2">Cycle count</param> + <param index="3">Cycle time (seconds, decimal)</param> + <param index="4">Empty</param> + <param index="5">Empty</param> + <param index="6">Empty</param> + <param index="7">Empty</param> + </entry> + <entry value="183" name="MAV_CMD_DO_SET_SERVO"> + <description>Set a servo to a desired PWM value.</description> + <param index="1">Servo number</param> + <param index="2">PWM (microseconds, 1000 to 2000 typical)</param> + <param index="3">Empty</param> + <param index="4">Empty</param> + <param index="5">Empty</param> + <param index="6">Empty</param> + <param index="7">Empty</param> + </entry> + <entry value="184" name="MAV_CMD_DO_REPEAT_SERVO"> + <description>Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period.</description> + <param index="1">Servo number</param> + <param index="2">PWM (microseconds, 1000 to 2000 typical)</param> + <param index="3">Cycle count</param> + <param index="4">Cycle time (seconds)</param> + <param index="5">Empty</param> + <param index="6">Empty</param> + <param index="7">Empty</param> + </entry> + <entry value="200" name="MAV_CMD_DO_CONTROL_VIDEO"> + <description>Control onboard camera capturing.</description> + <param index="1">Camera ID (-1 for all)</param> + <param index="2">Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw</param> + <param index="3">Transmission mode: 0: video stream, >0: single images every n seconds (decimal)</param> + <param index="4">Recording: 0: disabled, 1: enabled compressed, 2: enabled raw</param> + <param index="5">Empty</param> + <param index="6">Empty</param> + <param index="7">Empty</param> + </entry> + <entry value="201" name="MAV_CMD_DO_SET_ROI"> + <description>Sets the region of interest (ROI) for a sensor set or the + vehicle itself. This can then be used by the vehicles control + system to control the vehicle attitude and the attitude of various + devices such as cameras. + </description> + <param index="1">Region of interest mode. (see MAV_ROI enum)</param> + <param index="2">Waypoint index/ target ID. (see MAV_ROI enum)</param> + <param index="3">ROI index (allows a vehicle to manage multiple cameras etc.)</param> + <param index="4">Empty</param> + <param index="5">x the location of the fixed ROI (see MAV_FRAME)</param> + <param index="6">y</param> + <param index="7">z</param> + </entry> + <entry value="240" name="MAV_CMD_DO_LAST"> + <description>NOP - This command is only used to mark the upper limit of the DO commands in the enumeration</description> + <param index="1">Empty</param> + <param index="2">Empty</param> + <param index="3">Empty</param> + <param index="4">Empty</param> + <param index="5">Empty</param> + <param index="6">Empty</param> + <param index="7">Empty</param> + </entry> + <entry value="241" name="MAV_CMD_PREFLIGHT_CALIBRATION"> + <description>Trigger calibration. This command will be only accepted if in pre-flight mode.</description> + <param index="1">Gyro calibration: 0: no, 1: yes</param> + <param index="2">Magnetometer calibration: 0: no, 1: yes</param> + <param index="3">Ground pressure: 0: no, 1: yes</param> + <param index="4">Radio calibration: 0: no, 1: yes</param> + <param index="5">Empty</param> + <param index="6">Empty</param> + <param index="7">Empty</param> + </entry> + <entry value="245" name="MAV_CMD_PREFLIGHT_STORAGE"> + <description>Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode.</description> + <param index="1">Parameter storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM</param> + <param index="2">Mission storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM</param> + <param index="3">Reserved</param> + <param index="4">Reserved</param> + <param index="5">Empty</param> + <param index="6">Empty</param> + <param index="7">Empty</param> + </entry> + </enum> + <enum name="MAV_DATA_STREAM"> + <description>Data stream IDs. A data stream is not a fixed set of messages, but rather a + recommendation to the autopilot software. Individual autopilots may or may not obey + the recommended messages. + </description> + <entry value="0" name="MAV_DATA_STREAM_ALL"> + <description>Enable all data streams</description> + </entry> + <entry value="1" name="MAV_DATA_STREAM_RAW_SENSORS"> + <description>Enable IMU_RAW, GPS_RAW, GPS_STATUS packets.</description> + </entry> + <entry value="2" name="MAV_DATA_STREAM_EXTENDED_STATUS"> + <description>Enable GPS_STATUS, CONTROL_STATUS, AUX_STATUS</description> + </entry> + <entry value="3" name="MAV_DATA_STREAM_RC_CHANNELS"> + <description>Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW</description> + </entry> + <entry value="4" name="MAV_DATA_STREAM_RAW_CONTROLLER"> + <description>Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, NAV_CONTROLLER_OUTPUT.</description> + </entry> + <entry value="6" name="MAV_DATA_STREAM_POSITION"> + <description>Enable LOCAL_POSITION, GLOBAL_POSITION/GLOBAL_POSITION_INT messages.</description> + </entry> + <entry value="10" name="MAV_DATA_STREAM_EXTRA1"> + <description>Dependent on the autopilot</description> + </entry> + <entry value="11" name="MAV_DATA_STREAM_EXTRA2"> + <description>Dependent on the autopilot</description> + </entry> + <entry value="12" name="MAV_DATA_STREAM_EXTRA3"> + <description>Dependent on the autopilot</description> + </entry> + </enum> + <enum name="MAV_ROI"> + <description> The ROI (region of interest) for the vehicle. This can be + be used by the vehicle for camera/vehicle attitude alignment (see + MAV_CMD_NAV_ROI). + </description> + <entry value="0" name="MAV_ROI_NONE"> + <description>No region of interest.</description> + </entry> + <entry value="1" name="MAV_ROI_WPNEXT"> + <description>Point toward next waypoint.</description> + </entry> + <entry value="2" name="MAV_ROI_WPINDEX"> + <description>Point toward given waypoint.</description> + </entry> + <entry value="3" name="MAV_ROI_LOCATION"> + <description>Point toward fixed location.</description> + </entry> + <entry value="4" name="MAV_ROI_TARGET"> + <description>Point toward of given id.</description> + </entry> + </enum> + </enums> + <messages> + <message id="0" name="HEARTBEAT"> + <description>The heartbeat message shows that a system is present and responding. The type of the MAV and Autopilot hardware allow the receiving system to treat further messages from this system appropriate (e.g. by laying out the user interface based on the autopilot).</description> + <field type="uint8_t" name="type">Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)</field> + <field type="uint8_t" name="autopilot">Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM</field> + <field type="uint8_t_mavlink_version" name="mavlink_version">MAVLink version</field> + </message> + <message id="1" name="BOOT"> + <description>The boot message indicates that a system is starting. The onboard software version allows to keep track of onboard soft/firmware revisions.</description> + <field type="uint32_t" name="version">The onboard software version</field> + </message> + <message id="2" name="SYSTEM_TIME"> + <description>The system time is the time of the master clock, typically the computer clock of the main onboard computer.</description> + <field type="uint64_t" name="time_usec">Timestamp of the master clock in microseconds since UNIX epoch.</field> + </message> + <message id="3" name="PING"> + <description>A ping message either requesting or responding to a ping. This allows to measure the system latencies, including serial port, radio modem and UDP connections.</description> + <field type="uint32_t" name="seq">PING sequence</field> + <field type="uint8_t" name="target_system">0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system</field> + <field type="uint8_t" name="target_component">0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system</field> + <field type="uint64_t" name="time">Unix timestamp in microseconds</field> + </message> + <message id="4" name="SYSTEM_TIME_UTC"> + <description>UTC date and time from GPS module</description> + <field type="uint32_t" name="utc_date">GPS UTC date ddmmyy</field> + <field type="uint32_t" name="utc_time">GPS UTC time hhmmss</field> + </message> + <message id="5" name="CHANGE_OPERATOR_CONTROL"> + <description>Request to control this MAV</description> + <field type="uint8_t" name="target_system">System the GCS requests control for</field> + <field type="uint8_t" name="control_request">0: request control of this MAV, 1: Release control of this MAV</field> + <field type="uint8_t" name="version">0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch.</field> + <field type="char[25]" name="passkey">Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-"</field> + </message> + <message id="6" name="CHANGE_OPERATOR_CONTROL_ACK"> + <description>Accept / deny control of this MAV</description> + <field type="uint8_t" name="gcs_system_id">ID of the GCS this message </field> + <field type="uint8_t" name="control_request">0: request control of this MAV, 1: Release control of this MAV</field> + <field type="uint8_t" name="ack">0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control</field> + </message> + <message id="7" name="AUTH_KEY"> + <description>Emit an encrypted signature / key identifying this system. PLEASE NOTE: This protocol has been kept simple, so transmitting the key requires an encrypted channel for true safety.</description> + <field type="char[32]" name="key">key</field> + </message> + <message id="9" name="ACTION_ACK"> + <description>This message acknowledges an action. IMPORTANT: The acknowledgement can be also negative, e.g. the MAV rejects a reset message because it is in-flight. The action ids are defined in ENUM MAV_ACTION in mavlink/include/mavlink_types.h</description> + <field type="uint8_t" name="action">The action id</field> + <field type="uint8_t" name="result">0: Action DENIED, 1: Action executed</field> + </message> + <message id="10" name="ACTION"> + <description>An action message allows to execute a certain onboard action. These include liftoff, land, storing parameters too EEPROM, shutddown, etc. The action ids are defined in ENUM MAV_ACTION in mavlink/include/mavlink_types.h</description> + <field type="uint8_t" name="target">The system executing the action</field> + <field type="uint8_t" name="target_component">The component executing the action</field> + <field type="uint8_t" name="action">The action id</field> + </message> + <message id="11" name="SET_MODE"> + <description>Set the system mode, as defined by enum MAV_MODE in mavlink/include/mavlink_types.h. There is no target component id as the mode is by definition for the overall aircraft, not only for one component.</description> + <field type="uint8_t" name="target">The system setting the mode</field> + <field type="uint8_t" name="mode">The new mode</field> + </message> + <message id="12" name="SET_NAV_MODE"> + <description>Set the system navigation mode, as defined by enum MAV_NAV_MODE in mavlink/include/mavlink_types.h. The navigation mode applies to the whole aircraft and thus all components.</description> + <field type="uint8_t" name="target">The system setting the mode</field> + <field type="uint8_t" name="nav_mode">The new navigation mode</field> + </message> + <message id="20" name="PARAM_REQUEST_READ"> + <description>Request to read the onboard parameter with the param_id string id. Onboard parameters are stored as key[const char*] -> value[float]. This allows to send a parameter to any other component (such as the GCS) without the need of previous knowledge of possible parameter names. Thus the same GCS can store different parameters for different autopilots. See also http://qgroundcontrol.org/parameter_interface for a full documentation of QGroundControl and IMU code.</description> + <field type="uint8_t" name="target_system">System ID</field> + <field type="uint8_t" name="target_component">Component ID</field> + <field type="array[15]" name="param_id">Onboard parameter id</field> + <field type="int16_t" name="param_index">Parameter index. Send -1 to use the param ID field as identifier</field> + </message> + <message id="21" name="PARAM_REQUEST_LIST"> + <description>Request all parameters of this component. After his request, all parameters are emitted.</description> + <field type="uint8_t" name="target_system">System ID</field> + <field type="uint8_t" name="target_component">Component ID</field> + </message> + <message id="22" name="PARAM_VALUE"> + <description>Emit the value of a onboard parameter. The inclusion of param_count and param_index in the message allows the recipient to keep track of received parameters and allows him to re-request missing parameters after a loss or timeout.</description> + <field type="array[15]" name="param_id">Onboard parameter id</field> + <field type="float" name="param_value">Onboard parameter value</field> + <field type="uint16_t" name="param_count">Total number of onboard parameters</field> + <field type="uint16_t" name="param_index">Index of this onboard parameter</field> + </message> + <message id="23" name="PARAM_SET"> + <description>Set a parameter value TEMPORARILY to RAM. It will be reset to default on system reboot. Send the ACTION MAV_ACTION_STORAGE_WRITE to PERMANENTLY write the RAM contents to EEPROM. IMPORTANT: The receiving component should acknowledge the new parameter value by sending a param_value message to all communication partners. This will also ensure that multiple GCS all have an up-to-date list of all parameters. If the sending GCS did not receive a PARAM_VALUE message within its timeout time, it should re-send the PARAM_SET message.</description> + <field type="uint8_t" name="target_system">System ID</field> + <field type="uint8_t" name="target_component">Component ID</field> + <field type="array[15]" name="param_id">Onboard parameter id</field> + <field type="float" name="param_value">Onboard parameter value</field> + </message> + <message id="25" name="GPS_RAW_INT"> + <description>The global position, as returned by the Global Positioning System (GPS). This is +NOT the global position estimate of the sytem, but rather a RAW sensor value. See message GLOBAL_POSITION for the global position estimate. Coordinate frame is right-handed, Z-axis up (GPS frame)</description> + <field type="uint64_t" name="usec">Timestamp (microseconds since UNIX epoch or microseconds since system boot)</field> + <field type="uint8_t" name="fix_type">0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.</field> + <field type="int32_t" name="lat">Latitude in 1E7 degrees</field> + <field type="int32_t" name="lon">Longitude in 1E7 degrees</field> + <field type="int32_t" name="alt">Altitude in 1E3 meters (millimeters)</field> + <field type="float" name="eph">GPS HDOP</field> + <field type="float" name="epv">GPS VDOP</field> + <field type="float" name="v">GPS ground speed (m/s)</field> + <field type="float" name="hdg">Compass heading in degrees, 0..360 degrees</field> + </message> + <message id="26" name="SCALED_IMU"> + <description>The RAW IMU readings for the usual 9DOF sensor setup. This message should contain the scaled values to the described units</description> + <field type="uint64_t" name="usec">Timestamp (microseconds since UNIX epoch or microseconds since system boot)</field> + <field type="int16_t" name="xacc">X acceleration (mg)</field> + <field type="int16_t" name="yacc">Y acceleration (mg)</field> + <field type="int16_t" name="zacc">Z acceleration (mg)</field> + <field type="int16_t" name="xgyro">Angular speed around X axis (millirad /sec)</field> + <field type="int16_t" name="ygyro">Angular speed around Y axis (millirad /sec)</field> + <field type="int16_t" name="zgyro">Angular speed around Z axis (millirad /sec)</field> + <field type="int16_t" name="xmag">X Magnetic field (milli tesla)</field> + <field type="int16_t" name="ymag">Y Magnetic field (milli tesla)</field> + <field type="int16_t" name="zmag">Z Magnetic field (milli tesla)</field> + </message> + <message id="27" name="GPS_STATUS"> + <description>The positioning status, as reported by GPS. This message is intended to display status information about each satellite visible to the receiver. See message GLOBAL_POSITION for the global position estimate. This message can contain information for up to 20 satellites.</description> + <field type="uint8_t" name="satellites_visible">Number of satellites visible</field> + <field type="array[20]" name="satellite_prn">Global satellite ID</field> + <field type="array[20]" name="satellite_used">0: Satellite not used, 1: used for localization</field> + <field type="array[20]" name="satellite_elevation">Elevation (0: right on top of receiver, 90: on the horizon) of satellite</field> + <field type="array[20]" name="satellite_azimuth">Direction of satellite, 0: 0 deg, 255: 360 deg.</field> + <field type="array[20]" name="satellite_snr">Signal to noise ratio of satellite</field> + </message> + <message id="28" name="RAW_IMU"> + <description>The RAW IMU readings for the usual 9DOF sensor setup. This message should always contain the true raw values without any scaling to allow data capture and system debugging.</description> + <field type="uint64_t" name="usec">Timestamp (microseconds since UNIX epoch or microseconds since system boot)</field> + <field type="int16_t" name="xacc">X acceleration (raw)</field> + <field type="int16_t" name="yacc">Y acceleration (raw)</field> + <field type="int16_t" name="zacc">Z acceleration (raw)</field> + <field type="int16_t" name="xgyro">Angular speed around X axis (raw)</field> + <field type="int16_t" name="ygyro">Angular speed around Y axis (raw)</field> + <field type="int16_t" name="zgyro">Angular speed around Z axis (raw)</field> + <field type="int16_t" name="xmag">X Magnetic field (raw)</field> + <field type="int16_t" name="ymag">Y Magnetic field (raw)</field> + <field type="int16_t" name="zmag">Z Magnetic field (raw)</field> + </message> + <message id="29" name="RAW_PRESSURE"> + <description>The RAW pressure readings for the typical setup of one absolute pressure and one differential pressure sensor. The sensor values should be the raw, UNSCALED ADC values.</description> + <field type="uint64_t" name="usec">Timestamp (microseconds since UNIX epoch or microseconds since system boot)</field> + <field type="int16_t" name="press_abs">Absolute pressure (raw)</field> + <field type="int16_t" name="press_diff1">Differential pressure 1 (raw)</field> + <field type="int16_t" name="press_diff2">Differential pressure 2 (raw)</field> + <field type="int16_t" name="temperature">Raw Temperature measurement (raw)</field> + </message> + <message id="38" name="SCALED_PRESSURE"> + <description>The pressure readings for the typical setup of one absolute and differential pressure sensor. The units are as specified in each field.</description> + <field type="uint64_t" name="usec">Timestamp (microseconds since UNIX epoch or microseconds since system boot)</field> + <field type="float" name="press_abs">Absolute pressure (hectopascal)</field> + <field type="float" name="press_diff">Differential pressure 1 (hectopascal)</field> + <field type="int16_t" name="temperature">Temperature measurement (0.01 degrees celsius)</field> + </message> + <message id="30" name="ATTITUDE"> + <description>The attitude in the aeronautical frame (right-handed, Z-down, X-front, Y-right).</description> + <field type="uint64_t" name="usec">Timestamp (microseconds since UNIX epoch or microseconds since system boot)</field> + <field type="float" name="roll">Roll angle (rad)</field> + <field type="float" name="pitch">Pitch angle (rad)</field> + <field type="float" name="yaw">Yaw angle (rad)</field> + <field type="float" name="rollspeed">Roll angular speed (rad/s)</field> + <field type="float" name="pitchspeed">Pitch angular speed (rad/s)</field> + <field type="float" name="yawspeed">Yaw angular speed (rad/s)</field> + </message> + <message id="31" name="LOCAL_POSITION"> + <description>The filtered local position (e.g. fused computer vision and accelerometers). Coordinate frame is right-handed, Z-axis down (aeronautical frame)</description> + <field type="uint64_t" name="usec">Timestamp (microseconds since UNIX epoch or microseconds since system boot)</field> + <field type="float" name="x">X Position</field> + <field type="float" name="y">Y Position</field> + <field type="float" name="z">Z Position</field> + <field type="float" name="vx">X Speed</field> + <field type="float" name="vy">Y Speed</field> + <field type="float" name="vz">Z Speed</field> + </message> + <message id="33" name="GLOBAL_POSITION"> + <description>The filtered global position (e.g. fused GPS and accelerometers). Coordinate frame is right-handed, Z-axis up (GPS frame)</description> + <field type="uint64_t" name="usec">Timestamp (microseconds since unix epoch)</field> + <field type="float" name="lat">Latitude, in degrees</field> + <field type="float" name="lon">Longitude, in degrees</field> + <field type="float" name="alt">Absolute altitude, in meters</field> + <field type="float" name="vx">X Speed (in Latitude direction, positive: going north)</field> + <field type="float" name="vy">Y Speed (in Longitude direction, positive: going east)</field> + <field type="float" name="vz">Z Speed (in Altitude direction, positive: going up)</field> + </message> + <message id="32" name="GPS_RAW"> + <description>The global position, as returned by the Global Positioning System (GPS). This is +NOT the global position estimate of the sytem, but rather a RAW sensor value. See message GLOBAL_POSITION for the global position estimate. Coordinate frame is right-handed, Z-axis up (GPS frame)</description> + <field type="uint64_t" name="usec">Timestamp (microseconds since UNIX epoch or microseconds since system boot)</field> + <field type="uint8_t" name="fix_type">0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.</field> + <field type="float" name="lat">Latitude in degrees</field> + <field type="float" name="lon">Longitude in degrees</field> + <field type="float" name="alt">Altitude in meters</field> + <field type="float" name="eph">GPS HDOP</field> + <field type="float" name="epv">GPS VDOP</field> + <field type="float" name="v">GPS ground speed</field> + <field type="float" name="hdg">Compass heading in degrees, 0..360 degrees</field> + </message> + <message id="34" name="SYS_STATUS"> + <description>The general system state. If the system is following the MAVLink standard, the system state is mainly defined by three orthogonal states/modes: The system mode, which is either LOCKED (motors shut down and locked), MANUAL (system under RC control), GUIDED (system with autonomous position control, position setpoint controlled manually) or AUTO (system guided by path/waypoint planner). The NAV_MODE defined the current flight state: LIFTOFF (often an open-loop maneuver), LANDING, WAYPOINTS or VECTOR. This represents the internal navigation state machine. The system status shows wether the system is currently active or not and if an emergency occured. During the CRITICAL and EMERGENCY states the MAV is still considered to be active, but should start emergency procedures autonomously. After a failure occured it should first move from active to critical to allow manual intervention and then move to emergency after a certain timeout.</description> + <field type="uint8_t" name="mode">System mode, see MAV_MODE ENUM in mavlink/include/mavlink_types.h</field> + <field type="uint8_t" name="nav_mode">Navigation mode, see MAV_NAV_MODE ENUM</field> + <field type="uint8_t" name="status">System status flag, see MAV_STATUS ENUM</field> + <field type="uint16_t" name="load">Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000</field> + <field type="uint16_t" name="vbat">Battery voltage, in millivolts (1 = 1 millivolt)</field> + <field type="uint16_t" name="battery_remaining">Remaining battery energy: (0%: 0, 100%: 1000)</field> + <field type="uint16_t" name="packet_drop">Dropped packets (packets that were corrupted on reception on the MAV)</field> + </message> + <message id="35" name="RC_CHANNELS_RAW"> + <description>The RAW values of the RC channels received. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. Individual receivers/transmitters might violate this specification.</description> + <field type="uint16_t" name="chan1_raw">RC channel 1 value, in microseconds</field> + <field type="uint16_t" name="chan2_raw">RC channel 2 value, in microseconds</field> + <field type="uint16_t" name="chan3_raw">RC channel 3 value, in microseconds</field> + <field type="uint16_t" name="chan4_raw">RC channel 4 value, in microseconds</field> + <field type="uint16_t" name="chan5_raw">RC channel 5 value, in microseconds</field> + <field type="uint16_t" name="chan6_raw">RC channel 6 value, in microseconds</field> + <field type="uint16_t" name="chan7_raw">RC channel 7 value, in microseconds</field> + <field type="uint16_t" name="chan8_raw">RC channel 8 value, in microseconds</field> + <field type="uint8_t" name="rssi">Receive signal strength indicator, 0: 0%, 255: 100%</field> + </message> + <message id="36" name="RC_CHANNELS_SCALED"> + <description>The scaled values of the RC channels received. (-100%) -10000, (0%) 0, (100%) 10000</description> + <field type="int16_t" name="chan1_scaled">RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000</field> + <field type="int16_t" name="chan2_scaled">RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000</field> + <field type="int16_t" name="chan3_scaled">RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000</field> + <field type="int16_t" name="chan4_scaled">RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000</field> + <field type="int16_t" name="chan5_scaled">RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000</field> + <field type="int16_t" name="chan6_scaled">RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000</field> + <field type="int16_t" name="chan7_scaled">RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000</field> + <field type="int16_t" name="chan8_scaled">RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000</field> + <field type="uint8_t" name="rssi">Receive signal strength indicator, 0: 0%, 255: 100%</field> + </message> + <message id="37" name="SERVO_OUTPUT_RAW"> + <description>The RAW values of the servo outputs (for RC input from the remote, use the RC_CHANNELS messages). The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%.</description> + <field type="uint16_t" name="servo1_raw">Servo output 1 value, in microseconds</field> + <field type="uint16_t" name="servo2_raw">Servo output 2 value, in microseconds</field> + <field type="uint16_t" name="servo3_raw">Servo output 3 value, in microseconds</field> + <field type="uint16_t" name="servo4_raw">Servo output 4 value, in microseconds</field> + <field type="uint16_t" name="servo5_raw">Servo output 5 value, in microseconds</field> + <field type="uint16_t" name="servo6_raw">Servo output 6 value, in microseconds</field> + <field type="uint16_t" name="servo7_raw">Servo output 7 value, in microseconds</field> + <field type="uint16_t" name="servo8_raw">Servo output 8 value, in microseconds</field> + </message> + <message id="39" name="WAYPOINT"> + <description>Message encoding a waypoint. This message is emitted to announce + the presence of a waypoint and to set a waypoint on the system. The waypoint can be either in x, y, z meters (type: LOCAL) or x:lat, y:lon, z:altitude. Local frame is Z-down, right handed, global frame is Z-up, right handed</description> + <field type="uint8_t" name="target_system">System ID</field> + <field type="uint8_t" name="target_component">Component ID</field> + <field type="uint16_t" name="seq">Sequence</field> + <field type="uint8_t" name="frame">The coordinate system of the waypoint. see MAV_FRAME in mavlink_types.h</field> + <field type="uint8_t" name="command">The scheduled action for the waypoint. see MAV_COMMAND in common.xml MAVLink specs</field> + <field type="uint8_t" name="current">false:0, true:1</field> + <field type="uint8_t" name="autocontinue">autocontinue to next wp</field> + <field type="float" name="param1">PARAM1 / For NAV command waypoints: Radius in which the waypoint is accepted as reached, in meters</field> + <field type="float" name="param2">PARAM2 / For NAV command waypoints: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds</field> + <field type="float" name="param3">PARAM3 / For LOITER command waypoints: Orbit to circle around the waypoint, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise.</field> + <field type="float" name="param4">PARAM4 / For NAV and LOITER command waypoints: Yaw orientation in degrees, [0..360] 0 = NORTH</field> + <field type="float" name="x">PARAM5 / local: x position, global: latitude</field> + <field type="float" name="y">PARAM6 / y position: global: longitude</field> + <field type="float" name="z">PARAM7 / z position: global: altitude</field> + </message> + <message id="40" name="WAYPOINT_REQUEST"> + <description>Request the information of the waypoint with the sequence number seq. The response of the system to this message should be a WAYPOINT message.</description> + <field type="uint8_t" name="target_system">System ID</field> + <field type="uint8_t" name="target_component">Component ID</field> + <field type="uint16_t" name="seq">Sequence</field> + </message> + <message id="41" name="WAYPOINT_SET_CURRENT"> + <description>Set the waypoint with sequence number seq as current waypoint. This means that the MAV will continue to this waypoint on the shortest path (not following the waypoints in-between).</description> + <field type="uint8_t" name="target_system">System ID</field> + <field type="uint8_t" name="target_component">Component ID</field> + <field type="uint16_t" name="seq">Sequence</field> + </message> + <message id="42" name="WAYPOINT_CURRENT"> + <description>Message that announces the sequence number of the current active waypoint. The MAV will fly towards this waypoint.</description> + <field type="uint16_t" name="seq">Sequence</field> + </message> + <message id="43" name="WAYPOINT_REQUEST_LIST"> + <description>Request the overall list of waypoints from the system/component.</description> + <field type="uint8_t" name="target_system">System ID</field> + <field type="uint8_t" name="target_component">Component ID</field> + </message> + <message id="44" name="WAYPOINT_COUNT"> + <description>This message is emitted as response to WAYPOINT_REQUEST_LIST by the MAV. The GCS can then request the individual waypoints based on the knowledge of the total number of waypoints.</description> + <field type="uint8_t" name="target_system">System ID</field> + <field type="uint8_t" name="target_component">Component ID</field> + <field type="uint16_t" name="count">Number of Waypoints in the Sequence</field> + </message> + <message id="45" name="WAYPOINT_CLEAR_ALL"> + <description>Delete all waypoints at once.</description> + <field type="uint8_t" name="target_system">System ID</field> + <field type="uint8_t" name="target_component">Component ID</field> + </message> + <message id="46" name="WAYPOINT_REACHED"> + <description>A certain waypoint has been reached. The system will either hold this position (or circle on the orbit) or (if the autocontinue on the WP was set) continue to the next waypoint.</description> + <field type="uint16_t" name="seq">Sequence</field> + </message> + <message id="47" name="WAYPOINT_ACK"> + <description>Ack message during waypoint handling. The type field states if this message is a positive ack (type=0) or if an error happened (type=non-zero).</description> + <field type="uint8_t" name="target_system">System ID</field> + <field type="uint8_t" name="target_component">Component ID</field> + <field type="uint8_t" name="type">0: OK, 1: Error</field> + </message> + <message id="48" name="GPS_SET_GLOBAL_ORIGIN"> + <description>As local waypoints exist, the global waypoint reference allows to transform between the local coordinate frame and the global (GPS) coordinate frame. This can be necessary when e.g. in- and outdoor settings are connected and the MAV should move from in- to outdoor.</description> + <field type="uint8_t" name="target_system">System ID</field> + <field type="uint8_t" name="target_component">Component ID</field> + <field type="int32_t" name="latitude">global position * 1E7</field> + <field type="int32_t" name="longitude">global position * 1E7</field> + <field type="int32_t" name="altitude">global position * 1000</field> + </message> + <message id="49" name="GPS_LOCAL_ORIGIN_SET"> + <description>Once the MAV sets a new GPS-Local correspondence, this message announces the origin (0,0,0) position</description> + <field type="int32_t" name="latitude">Latitude (WGS84), expressed as * 1E7</field> + <field type="int32_t" name="longitude">Longitude (WGS84), expressed as * 1E7</field> + <field type="int32_t" name="altitude">Altitude(WGS84), expressed as * 1000</field> + </message> + <message id="50" name="LOCAL_POSITION_SETPOINT_SET"> + <description>Set the setpoint for a local position controller. This is the position in local coordinates the MAV should fly to. This message is sent by the path/waypoint planner to the onboard position controller. As some MAVs have a degree of freedom in yaw (e.g. all helicopters/quadrotors), the desired yaw angle is part of the message.</description> + <field type="uint8_t" name="target_system">System ID</field> + <field type="uint8_t" name="target_component">Component ID</field> + <field type="float" name="x">x position</field> + <field type="float" name="y">y position</field> + <field type="float" name="z">z position</field> + <field type="float" name="yaw">Desired yaw angle</field> + </message> + <message id="51" name="LOCAL_POSITION_SETPOINT"> + <description>Transmit the current local setpoint of the controller to other MAVs (collision avoidance) and to the GCS.</description> + <field type="float" name="x">x position</field> + <field type="float" name="y">y position</field> + <field type="float" name="z">z position</field> + <field type="float" name="yaw">Desired yaw angle</field> + </message> + <message id="52" name="CONTROL_STATUS"> + <field type="uint8_t" name="position_fix">Position fix: 0: lost, 2: 2D position fix, 3: 3D position fix </field> + <field type="uint8_t" name="vision_fix">Vision position fix: 0: lost, 1: 2D local position hold, 2: 2D global position fix, 3: 3D global position fix </field> + <field type="uint8_t" name="gps_fix">GPS position fix: 0: no reception, 1: Minimum 1 satellite, but no position fix, 2: 2D position fix, 3: 3D position fix </field> + <field type="uint8_t" name="ahrs_health">Attitude estimation health: 0: poor, 255: excellent</field> + <field type="uint8_t" name="control_att">0: Attitude control disabled, 1: enabled</field> + <field type="uint8_t" name="control_pos_xy">0: X, Y position control disabled, 1: enabled</field> + <field type="uint8_t" name="control_pos_z">0: Z position control disabled, 1: enabled</field> + <field type="uint8_t" name="control_pos_yaw">0: Yaw angle control disabled, 1: enabled</field> + </message> + <message id="53" name="SAFETY_SET_ALLOWED_AREA"> + <description>Set a safety zone (volume), which is defined by two corners of a cube. This message can be used to tell the MAV which setpoints/waypoints to accept and which to reject. Safety areas are often enforced by national or competition regulations.</description> + <field type="uint8_t" name="target_system">System ID</field> + <field type="uint8_t" name="target_component">Component ID</field> + <field type="uint8_t" name="frame">Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down.</field> + <field type="float" name="p1x">x position 1 / Latitude 1</field> + <field type="float" name="p1y">y position 1 / Longitude 1</field> + <field type="float" name="p1z">z position 1 / Altitude 1</field> + <field type="float" name="p2x">x position 2 / Latitude 2</field> + <field type="float" name="p2y">y position 2 / Longitude 2</field> + <field type="float" name="p2z">z position 2 / Altitude 2</field> + </message> + <message id="54" name="SAFETY_ALLOWED_AREA"> + <description>Read out the safety zone the MAV currently assumes.</description> + <field type="uint8_t" name="frame">Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down.</field> + <field type="float" name="p1x">x position 1 / Latitude 1</field> + <field type="float" name="p1y">y position 1 / Longitude 1</field> + <field type="float" name="p1z">z position 1 / Altitude 1</field> + <field type="float" name="p2x">x position 2 / Latitude 2</field> + <field type="float" name="p2y">y position 2 / Longitude 2</field> + <field type="float" name="p2z">z position 2 / Altitude 2</field> + </message> + <message id="55" name="SET_ROLL_PITCH_YAW_THRUST"> + <description>Set roll, pitch and yaw.</description> + <field type="uint8_t" name="target_system">System ID</field> + <field type="uint8_t" name="target_component">Component ID</field> + <field type="float" name="roll">Desired roll angle in radians</field> + <field type="float" name="pitch">Desired pitch angle in radians</field> + <field type="float" name="yaw">Desired yaw angle in radians</field> + <field type="float" name="thrust">Collective thrust, normalized to 0 .. 1</field> + </message> + <message id="56" name="SET_ROLL_PITCH_YAW_SPEED_THRUST"> + <description>Set roll, pitch and yaw.</description> + <field type="uint8_t" name="target_system">System ID</field> + <field type="uint8_t" name="target_component">Component ID</field> + <field type="float" name="roll_speed">Desired roll angular speed in rad/s</field> + <field type="float" name="pitch_speed">Desired pitch angular speed in rad/s</field> + <field type="float" name="yaw_speed">Desired yaw angular speed in rad/s</field> + <field type="float" name="thrust">Collective thrust, normalized to 0 .. 1</field> + </message> + <message id="57" name="ROLL_PITCH_YAW_THRUST_SETPOINT"> + <description>Setpoint in roll, pitch, yaw currently active on the system.</description> + <field type="uint64_t" name="time_us">Timestamp in micro seconds since unix epoch</field> + <field type="float" name="roll">Desired roll angle in radians</field> + <field type="float" name="pitch">Desired pitch angle in radians</field> + <field type="float" name="yaw">Desired yaw angle in radians</field> + <field type="float" name="thrust">Collective thrust, normalized to 0 .. 1</field> + </message> + <message id="58" name="ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT"> + <description>Setpoint in rollspeed, pitchspeed, yawspeed currently active on the system.</description> + <field type="uint64_t" name="time_us">Timestamp in micro seconds since unix epoch</field> + <field type="float" name="roll_speed">Desired roll angular speed in rad/s</field> + <field type="float" name="pitch_speed">Desired pitch angular speed in rad/s</field> + <field type="float" name="yaw_speed">Desired yaw angular speed in rad/s</field> + <field type="float" name="thrust">Collective thrust, normalized to 0 .. 1</field> + </message> + <message id="62" name="NAV_CONTROLLER_OUTPUT"> + <description>Outputs of the APM navigation controller. The primary use of this message is to check the response and signs +of the controller before actual flight and to assist with tuning controller parameters </description> + <field type="float" name="nav_roll">Current desired roll in degrees</field> + <field type="float" name="nav_pitch">Current desired pitch in degrees</field> + <field type="int16_t" name="nav_bearing">Current desired heading in degrees</field> + <field type="int16_t" name="target_bearing">Bearing to current waypoint/target in degrees</field> + <field type="uint16_t" name="wp_dist">Distance to active waypoint in meters</field> + <field type="float" name="alt_error">Current altitude error in meters</field> + <field type="float" name="aspd_error">Current airspeed error in meters/second</field> + <field type="float" name="xtrack_error">Current crosstrack error on x-y plane in meters</field> + </message> + <message id="63" name="POSITION_TARGET"> + <description>The goal position of the system. This position is the input to any navigation or path planning algorithm and does NOT represent the current controller setpoint.</description> + <field type="float" name="x">x position</field> + <field type="float" name="y">y position</field> + <field type="float" name="z">z position</field> + <field type="float" name="yaw">yaw orientation in radians, 0 = NORTH</field> + </message> + <message id="64" name="STATE_CORRECTION"> + <description>Corrects the systems state by adding an error correction term to the position and velocity, and by rotating the attitude by a correction angle.</description> + <field type="float" name="xErr">x position error</field> + <field type="float" name="yErr">y position error</field> + <field type="float" name="zErr">z position error</field> + <field type="float" name="rollErr">roll error (radians)</field> + <field type="float" name="pitchErr">pitch error (radians)</field> + <field type="float" name="yawErr">yaw error (radians)</field> + <field type="float" name="vxErr">x velocity</field> + <field type="float" name="vyErr">y velocity</field> + <field type="float" name="vzErr">z velocity</field> + </message> + <message id="65" name="SET_ALTITUDE"> + <field type="uint8_t" name="target">The system setting the altitude</field> + <field type="uint32_t" name="mode">The new altitude in meters</field> + </message> + <message id="66" name="REQUEST_DATA_STREAM"> + <field type="uint8_t" name="target_system">The target requested to send the message stream.</field> + <field type="uint8_t" name="target_component">The target requested to send the message stream.</field> + <field type="uint8_t" name="req_stream_id">The ID of the requested message type</field> + <field type="uint16_t" name="req_message_rate">Update rate in Hertz</field> + <field type="uint8_t" name="start_stop">1 to start sending, 0 to stop sending.</field> + </message> + <message id="67" name="HIL_STATE"> + <description>This packet is useful for high throughput + applications such as hardware in the loop simulations. + </description> + <field type="uint64_t" name="usec">Timestamp (microseconds since UNIX epoch or microseconds since system boot)</field> + <field type="float" name="roll">Roll angle (rad)</field> + <field type="float" name="pitch">Pitch angle (rad)</field> + <field type="float" name="yaw">Yaw angle (rad)</field> + <field type="float" name="rollspeed">Roll angular speed (rad/s)</field> + <field type="float" name="pitchspeed">Pitch angular speed (rad/s)</field> + <field type="float" name="yawspeed">Yaw angular speed (rad/s)</field> + <field type="int32_t" name="lat">Latitude, expressed as * 1E7</field> + <field type="int32_t" name="lon">Longitude, expressed as * 1E7</field> + <field type="int32_t" name="alt">Altitude in meters, expressed as * 1000 (millimeters)</field> + <field type="int16_t" name="vx">Ground X Speed (Latitude), expressed as m/s * 100</field> + <field type="int16_t" name="vy">Ground Y Speed (Longitude), expressed as m/s * 100</field> + <field type="int16_t" name="vz">Ground Z Speed (Altitude), expressed as m/s * 100</field> + <field type="int16_t" name="xacc">X acceleration (mg)</field> + <field type="int16_t" name="yacc">Y acceleration (mg)</field> + <field type="int16_t" name="zacc">Z acceleration (mg)</field> + </message> + <message id="68" name="HIL_CONTROLS"> + <description>Hardware in the loop control outputs</description> + <field type="uint64_t" name="time_us">Timestamp (microseconds since UNIX epoch or microseconds since system boot)</field> + <field type="float" name="roll_ailerons">Control output -3 .. 1</field> + <field type="float" name="pitch_elevator">Control output -1 .. 1</field> + <field type="float" name="yaw_rudder">Control output -1 .. 1</field> + <field type="float" name="throttle">Throttle 0 .. 1</field> + <field type="uint8_t" name="mode">System mode (MAV_MODE)</field> + <field type="uint8_t" name="nav_mode">Navigation mode (MAV_NAV_MODE)</field> + </message> + <message id="69" name="MANUAL_CONTROL"> + <field type="uint8_t" name="target">The system to be controlled</field> + <field type="float" name="roll">roll</field> + <field type="float" name="pitch">pitch</field> + <field type="float" name="yaw">yaw</field> + <field type="float" name="thrust">thrust</field> + <field type="uint8_t" name="roll_manual">roll control enabled auto:0, manual:1</field> + <field type="uint8_t" name="pitch_manual">pitch auto:0, manual:1</field> + <field type="uint8_t" name="yaw_manual">yaw auto:0, manual:1</field> + <field type="uint8_t" name="thrust_manual">thrust auto:0, manual:1</field> + </message> + <message id="70" name="RC_CHANNELS_OVERRIDE"> + <description>The RAW values of the RC channels sent to the MAV to override info received from the RC radio. A value of -1 means no change to that channel. A value of 0 means control of that channel should be released back to the RC radio. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. Individual receivers/transmitters might violate this specification.</description> + <field type="uint8_t" name="target_system">System ID</field> + <field type="uint8_t" name="target_component">Component ID</field> + <field type="uint16_t" name="chan1_raw">RC channel 1 value, in microseconds</field> + <field type="uint16_t" name="chan2_raw">RC channel 2 value, in microseconds</field> + <field type="uint16_t" name="chan3_raw">RC channel 3 value, in microseconds</field> + <field type="uint16_t" name="chan4_raw">RC channel 4 value, in microseconds</field> + <field type="uint16_t" name="chan5_raw">RC channel 5 value, in microseconds</field> + <field type="uint16_t" name="chan6_raw">RC channel 6 value, in microseconds</field> + <field type="uint16_t" name="chan7_raw">RC channel 7 value, in microseconds</field> + <field type="uint16_t" name="chan8_raw">RC channel 8 value, in microseconds</field> + </message> + <message id="73" name="GLOBAL_POSITION_INT"> + <description>The filtered global position (e.g. fused GPS and accelerometers). The position is in GPS-frame (right-handed, Z-up)</description> + <field type="int32_t" name="lat">Latitude, expressed as * 1E7</field> + <field type="int32_t" name="lon">Longitude, expressed as * 1E7</field> + <field type="int32_t" name="alt">Altitude in meters, expressed as * 1000 (millimeters)</field> + <field type="int16_t" name="vx">Ground X Speed (Latitude), expressed as m/s * 100</field> + <field type="int16_t" name="vy">Ground Y Speed (Longitude), expressed as m/s * 100</field> + <field type="int16_t" name="vz">Ground Z Speed (Altitude), expressed as m/s * 100</field> + </message> + <message id="74" name="VFR_HUD"> + <description>Metrics typically displayed on a HUD for fixed wing aircraft</description> + <field type="float" name="airspeed">Current airspeed in m/s</field> + <field type="float" name="groundspeed">Current ground speed in m/s</field> + <field type="int16_t" name="heading">Current heading in degrees, in compass units (0..360, 0=north)</field> + <field type="uint16_t" name="throttle">Current throttle setting in integer percent, 0 to 100</field> + <field type="float" name="alt">Current altitude (MSL), in meters</field> + <field type="float" name="climb">Current climb rate in meters/second</field> + </message> + <message id="75" name="COMMAND"> + <description>Send a command with up to four parameters to the MAV</description> + <field type="uint8_t" name="target_system">System which should execute the command</field> + <field type="uint8_t" name="target_component">Component which should execute the command, 0 for all components</field> + <field type="uint8_t" name="command">Command ID, as defined by MAV_CMD enum.</field> + <field type="uint8_t" name="confirmation">0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command)</field> + <field type="float" name="param1">Parameter 1, as defined by MAV_CMD enum.</field> + <field type="float" name="param2">Parameter 2, as defined by MAV_CMD enum.</field> + <field type="float" name="param3">Parameter 3, as defined by MAV_CMD enum.</field> + <field type="float" name="param4">Parameter 4, as defined by MAV_CMD enum.</field> + </message> + <message id="76" name="COMMAND_ACK"> + <description>Report status of a command. Includes feedback wether the command was executed</description> + <field type="float" name="command">Current airspeed in m/s</field> + <field type="float" name="result">1: Action ACCEPTED and EXECUTED, 1: Action TEMPORARY REJECTED/DENIED, 2: Action PERMANENTLY DENIED, 3: Action UNKNOWN/UNSUPPORTED, 4: Requesting CONFIRMATION</field> + </message> + <message id="100" name="OPTICAL_FLOW"> + <description>Optical flow from a flow sensor (e.g. optical mouse sensor)</description> + <field type="uint64_t" name="time">Timestamp (UNIX)</field> + <field type="uint8_t" name="sensor_id">Sensor ID</field> + <field type="int16_t" name="flow_x">Flow in pixels in x-sensor direction</field> + <field type="int16_t" name="flow_y">Flow in pixels in y-sensor direction</field> + <field type="uint8_t" name="quality">Optical flow quality / confidence. 0: bad, 255: maximum quality</field> + <field type="float" name="ground_distance">Ground distance in meters</field> + </message> + <message id="140" name="OBJECT_DETECTION_EVENT"> + <description>Object has been detected</description> + <field type="uint32_t" name="time">Timestamp in milliseconds since system boot</field> + <field type="uint16_t" name="object_id">Object ID</field> + <field type="uint8_t" name="type">Object type: 0: image, 1: letter, 2: ground vehicle, 3: air vehicle, 4: surface vehicle, 5: sub-surface vehicle, 6: human, 7: animal</field> + <field type="char[20]" name="name">Name of the object as defined by the detector</field> + <field type="uint8_t" name="quality">Detection quality / confidence. 0: bad, 255: maximum confidence</field> + <field type="float" name="bearing">Angle of the object with respect to the body frame in NED coordinates in radians. 0: front</field> + <field type="float" name="distance">Ground distance in meters</field> + </message> + <!-- MESSAGE IDs 80 - 250: Space for custom messages in individual projectname_messages.xml files --> + <message id="251" name="DEBUG_VECT"> + <field type="char[10]" name="name">Name</field> + <field type="uint64_t" name="usec">Timestamp</field> + <field type="float" name="x">x</field> + <field type="float" name="y">y</field> + <field type="float" name="z">z</field> + </message> + <message id="252" name="NAMED_VALUE_FLOAT"> + <description>Send a key-value pair as float. The use of this message is discouraged for normal packets, but a quite efficient way for testing new messages and getting experimental debug output.</description> + <field type="char[10]" name="name">Name of the debug variable</field> + <field type="float" name="value">Floating point value</field> + </message> + <message id="253" name="NAMED_VALUE_INT"> + <description>Send a key-value pair as integer. The use of this message is discouraged for normal packets, but a quite efficient way for testing new messages and getting experimental debug output.</description> + <field type="char[10]" name="name">Name of the debug variable</field> + <field type="int32_t" name="value">Signed integer value</field> + </message> + <message id="254" name="STATUSTEXT"> + <description>Status text message. These messages are printed in yellow in the COMM console of QGroundControl. WARNING: They consume quite some bandwidth, so use only for important status and error messages. If implemented wisely, these messages are buffered on the MCU and sent only at a limited rate (e.g. 10 Hz).</description> + <field type="uint8_t" name="severity">Severity of status, 0 = info message, 255 = critical fault</field> + <field type="int8_t[50]" name="text">Status text message, without null termination character</field> + </message> + <message id="255" name="DEBUG"> + <description>Send a debug value. The index is used to discriminate between values. These values show up in the plot of QGroundControl as DEBUG N.</description> + <field type="uint8_t" name="ind">index of debug variable</field> + <field type="float" name="value">DEBUG value</field> + </message> + </messages> +</mavlink> diff --git a/libraries/GCS_MAVLink/message_definitions/minimal.xml b/libraries/GCS_MAVLink/message_definitions/minimal.xml new file mode 100644 index 0000000000000000000000000000000000000000..5b41a4909090112233c5b91d1fa3067d7ffbdcbf --- /dev/null +++ b/libraries/GCS_MAVLink/message_definitions/minimal.xml @@ -0,0 +1,13 @@ +<?xml version='1.0'?> +<mavlink> + <version>2</version> + <enums/> + <messages> + <message id="0" name="HEARTBEAT"> + <description>The heartbeat message shows that a system is present and responding. The type of the MAV and Autopilot hardware allow the receiving system to treat further messages from this system appropriate (e.g. by laying out the user interface based on the autopilot).</description> + <field type="uint8_t" name="type">Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)</field> + <field type="uint8_t" name="autopilot">Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM</field> + <field type="uint8_t_mavlink_version" name="mavlink_version">MAVLink version</field> + </message> + </messages> +</mavlink> diff --git a/libraries/GCS_MAVLink/message_definitions/pixhawk.xml b/libraries/GCS_MAVLink/message_definitions/pixhawk.xml new file mode 100644 index 0000000000000000000000000000000000000000..a9a51d698944431715810ead12b691db74d636af --- /dev/null +++ b/libraries/GCS_MAVLink/message_definitions/pixhawk.xml @@ -0,0 +1,227 @@ +<?xml version='1.0'?> +<mavlink> + <include>common.xml</include> + <enums> + <enum name="DATA_TYPES"> + <description>Content Types for data transmission handshake</description> + <entry value="1" name="DATA_TYPE_JPEG_IMAGE"/> + <entry value="2" name="DATA_TYPE_RAW_IMAGE"/> + <entry value="3" name="DATA_TYPE_KINECT"/> + </enum> + </enums> + <messages> + <message id="151" name="SET_CAM_SHUTTER"> + <field type="uint8_t" name="cam_no">Camera id</field> + <field type="uint8_t" name="cam_mode">Camera mode: 0 = auto, 1 = manual</field> + <field type="uint8_t" name="trigger_pin">Trigger pin, 0-3 for PtGrey FireFly</field> + <field type="uint16_t" name="interval">Shutter interval, in microseconds</field> + <field type="uint16_t" name="exposure">Exposure time, in microseconds</field> + <field type="float" name="gain">Camera gain</field> + </message> + <message id="152" name="IMAGE_TRIGGERED"> + <field type="uint64_t" name="timestamp">Timestamp</field> + <field type="uint32_t" name="seq">IMU seq</field> + <field type="float" name="roll">Roll angle in rad</field> + <field type="float" name="pitch">Pitch angle in rad</field> + <field type="float" name="yaw">Yaw angle in rad</field> + <field type="float" name="local_z">Local frame Z coordinate (height over ground)</field> + <field type="float" name="lat">GPS X coordinate</field> + <field type="float" name="lon">GPS Y coordinate</field> + <field type="float" name="alt">Global frame altitude</field> + <field type="float" name="ground_x">Ground truth X</field> + <field type="float" name="ground_y">Ground truth Y</field> + <field type="float" name="ground_z">Ground truth Z</field> + </message> + <message id="153" name="IMAGE_TRIGGER_CONTROL"> + <field type="uint8_t" name="enable">0 to disable, 1 to enable</field> + </message> + <message id="154" name="IMAGE_AVAILABLE"> + <field type="uint64_t" name="cam_id">Camera id</field> + <field type="uint8_t" name="cam_no">Camera # (starts with 0)</field> + <field type="uint64_t" name="timestamp">Timestamp</field> + <field type="uint64_t" name="valid_until">Until which timestamp this buffer will stay valid</field> + <field type="uint32_t" name="img_seq">The image sequence number</field> + <field type="uint32_t" name="img_buf_index">Position of the image in the buffer, starts with 0</field> + <field type="uint16_t" name="width">Image width</field> + <field type="uint16_t" name="height">Image height</field> + <field type="uint16_t" name="depth">Image depth</field> + <field type="uint8_t" name="channels">Image channels</field> + <field type="uint32_t" name="key">Shared memory area key</field> + <field type="uint32_t" name="exposure">Exposure time, in microseconds</field> + <field type="float" name="gain">Camera gain</field> + <field type="float" name="roll">Roll angle in rad</field> + <field type="float" name="pitch">Pitch angle in rad</field> + <field type="float" name="yaw">Yaw angle in rad</field> + <field type="float" name="local_z">Local frame Z coordinate (height over ground)</field> + <field type="float" name="lat">GPS X coordinate</field> + <field type="float" name="lon">GPS Y coordinate</field> + <field type="float" name="alt">Global frame altitude</field> + <field type="float" name="ground_x">Ground truth X</field> + <field type="float" name="ground_y">Ground truth Y</field> + <field type="float" name="ground_z">Ground truth Z</field> + </message> + <message id="156" name="VISION_POSITION_ESTIMATE"> + <field type="uint64_t" name="usec">Timestamp (milliseconds)</field> + <field type="float" name="x">Global X position</field> + <field type="float" name="y">Global Y position</field> + <field type="float" name="z">Global Z position</field> + <field type="float" name="roll">Roll angle in rad</field> + <field type="float" name="pitch">Pitch angle in rad</field> + <field type="float" name="yaw">Yaw angle in rad</field> + </message> + <message id="157" name="VICON_POSITION_ESTIMATE"> + <field type="uint64_t" name="usec">Timestamp (milliseconds)</field> + <field type="float" name="x">Global X position</field> + <field type="float" name="y">Global Y position</field> + <field type="float" name="z">Global Z position</field> + <field type="float" name="roll">Roll angle in rad</field> + <field type="float" name="pitch">Pitch angle in rad</field> + <field type="float" name="yaw">Yaw angle in rad</field> + </message> + <message id="158" name="VISION_SPEED_ESTIMATE"> + <field type="uint64_t" name="usec">Timestamp (milliseconds)</field> + <field type="float" name="x">Global X speed</field> + <field type="float" name="y">Global Y speed</field> + <field type="float" name="z">Global Z speed</field> + </message> + <message id="159" name="POSITION_CONTROL_SETPOINT_SET"> + <description>Message sent to the MAV to set a new position as reference for the controller</description> + <field type="uint8_t" name="target_system">System ID</field> + <field type="uint8_t" name="target_component">Component ID</field> + <field type="uint16_t" name="id">ID of waypoint, 0 for plain position</field> + <field type="float" name="x">x position</field> + <field type="float" name="y">y position</field> + <field type="float" name="z">z position</field> + <field type="float" name="yaw">yaw orientation in radians, 0 = NORTH</field> + </message> + <message id="160" name="POSITION_CONTROL_OFFSET_SET"> + <description>Message sent to the MAV to set a new offset from the currently controlled position</description> + <field type="uint8_t" name="target_system">System ID</field> + <field type="uint8_t" name="target_component">Component ID</field> + <field type="float" name="x">x position offset</field> + <field type="float" name="y">y position offset</field> + <field type="float" name="z">z position offset</field> + <field type="float" name="yaw">yaw orientation offset in radians, 0 = NORTH</field> + </message> + <!-- Message sent by the MAV once it sets a new position as reference in the controller --> + <message id="170" name="POSITION_CONTROL_SETPOINT"> + <field type="uint16_t" name="id">ID of waypoint, 0 for plain position</field> + <field type="float" name="x">x position</field> + <field type="float" name="y">y position</field> + <field type="float" name="z">z position</field> + <field type="float" name="yaw">yaw orientation in radians, 0 = NORTH</field> + </message> + <message id="171" name="MARKER"> + <field type="uint16_t" name="id">ID</field> + <field type="float" name="x">x position</field> + <field type="float" name="y">y position</field> + <field type="float" name="z">z position</field> + <field type="float" name="roll">roll orientation</field> + <field type="float" name="pitch">pitch orientation</field> + <field type="float" name="yaw">yaw orientation</field> + </message> + <message id="172" name="RAW_AUX"> + <field type="uint16_t" name="adc1">ADC1 (J405 ADC3, LPC2148 AD0.6)</field> + <field type="uint16_t" name="adc2">ADC2 (J405 ADC5, LPC2148 AD0.2)</field> + <field type="uint16_t" name="adc3">ADC3 (J405 ADC6, LPC2148 AD0.1)</field> + <field type="uint16_t" name="adc4">ADC4 (J405 ADC7, LPC2148 AD1.3)</field> + <field type="uint16_t" name="vbat">Battery voltage</field> + <field type="int16_t" name="temp">Temperature (degrees celcius)</field> + <field type="int32_t" name="baro">Barometric pressure (hecto Pascal)</field> + </message> + <message id="180" name="WATCHDOG_HEARTBEAT"> + <field type="uint16_t" name="watchdog_id">Watchdog ID</field> + <field type="uint16_t" name="process_count">Number of processes</field> + </message> + <message id="181" name="WATCHDOG_PROCESS_INFO"> + <field type="uint16_t" name="watchdog_id">Watchdog ID</field> + <field type="uint16_t" name="process_id">Process ID</field> + <field type="char[100]" name="name">Process name</field> + <field type="char[147]" name="arguments">Process arguments</field> + <field type="int32_t" name="timeout">Timeout (seconds)</field> + </message> + <message id="182" name="WATCHDOG_PROCESS_STATUS"> + <field type="uint16_t" name="watchdog_id">Watchdog ID</field> + <field type="uint16_t" name="process_id">Process ID</field> + <field type="uint8_t" name="state">Is running / finished / suspended / crashed</field> + <field type="uint8_t" name="muted">Is muted</field> + <field type="int32_t" name="pid">PID</field> + <field type="uint16_t" name="crashes">Number of crashes</field> + </message> + <message id="183" name="WATCHDOG_COMMAND"> + <field type="uint8_t" name="target_system_id">Target system ID</field> + <field type="uint16_t" name="watchdog_id">Watchdog ID</field> + <field type="uint16_t" name="process_id">Process ID</field> + <field type="uint8_t" name="command_id">Command ID</field> + </message> + <message id="190" name="PATTERN_DETECTED"> + <field type="uint8_t" name="type">0: Pattern, 1: Letter</field> + <field type="float" name="confidence">Confidence of detection</field> + <field type="char[100]" name="file">Pattern file name</field> + <field type="uint8_t" name="detected">Accepted as true detection, 0 no, 1 yes</field> + </message> + <message id="191" name="POINT_OF_INTEREST"> + <description>Notifies the operator about a point of interest (POI). This can be anything detected by the + system. This generic message is intented to help interfacing to generic visualizations and to display + the POI on a map. + </description> + <field type="uint8_t" name="type">0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug</field> + <field type="uint8_t" name="color">0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta</field> + <field type="uint8_t" name="coordinate_system">0: global, 1:local</field> + <field type="uint16_t" name="timeout">0: no timeout, >1: timeout in seconds</field> + <field type="float" name="x">X Position</field> + <field type="float" name="y">Y Position</field> + <field type="float" name="z">Z Position</field> + <field type="char[26]" name="name">POI name</field> + </message> + <message id="192" name="POINT_OF_INTEREST_CONNECTION"> + <description>Notifies the operator about the connection of two point of interests (POI). This can be anything detected by the + system. This generic message is intented to help interfacing to generic visualizations and to display + the POI on a map. + </description> + <field type="uint8_t" name="type">0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug</field> + <field type="uint8_t" name="color">0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta</field> + <field type="uint8_t" name="coordinate_system">0: global, 1:local</field> + <field type="uint16_t" name="timeout">0: no timeout, >1: timeout in seconds</field> + <field type="float" name="xp1">X1 Position</field> + <field type="float" name="yp1">Y1 Position</field> + <field type="float" name="zp1">Z1 Position</field> + <field type="float" name="xp2">X2 Position</field> + <field type="float" name="yp2">Y2 Position</field> + <field type="float" name="zp2">Z2 Position</field> + <field type="char[26]" name="name">POI connection name</field> + </message> + <message id="193" name="DATA_TRANSMISSION_HANDSHAKE"> + <field type="uint8_t" name="type">type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h)</field> + <field type="uint32_t" name="size">total data size in bytes (set on ACK only)</field> + <field type="uint8_t" name="packets">number of packets beeing sent (set on ACK only)</field> + <field type="uint8_t" name="payload">payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only)</field> + <field type="uint8_t" name="jpg_quality">JPEG quality out of [1,100]</field> + </message> + <message id="194" name="ENCAPSULATED_DATA"> + <field type="uint16_t" name="seqnr">sequence number (starting with 0 on every transmission)</field> + <field type="uint8_t[253]" name="data">image data bytes</field> + </message> + <message id="195" name="BRIEF_FEATURE"> + <field type="float" name="x">x position in m</field> + <field type="float" name="y">y position in m</field> + <field type="float" name="z">z position in m</field> + <field type="uint8_t" name="orientation_assignment">Orientation assignment 0: false, 1:true</field> + <field type="uint16_t" name="size">Size in pixels</field> + <field type="uint16_t" name="orientation">Orientation</field> + <field type="uint8_t[32]" name="descriptor">Descriptor</field> + <field type="float" name="response">Harris operator response at this location</field> + </message> + <message id="200" name="ATTITUDE_CONTROL"> + <field type="uint8_t" name="target">The system to be controlled</field> + <field type="float" name="roll">roll</field> + <field type="float" name="pitch">pitch</field> + <field type="float" name="yaw">yaw</field> + <field type="float" name="thrust">thrust</field> + <field type="uint8_t" name="roll_manual">roll control enabled auto:0, manual:1</field> + <field type="uint8_t" name="pitch_manual">pitch auto:0, manual:1</field> + <field type="uint8_t" name="yaw_manual">yaw auto:0, manual:1</field> + <field type="uint8_t" name="thrust_manual">thrust auto:0, manual:1</field> + </message> + </messages> +</mavlink> diff --git a/libraries/GCS_MAVLink/message_definitions/slugs.xml b/libraries/GCS_MAVLink/message_definitions/slugs.xml new file mode 100644 index 0000000000000000000000000000000000000000..5b7a9f7a5a7872f5fec3fa1f06680043054e553c --- /dev/null +++ b/libraries/GCS_MAVLink/message_definitions/slugs.xml @@ -0,0 +1,144 @@ +<?xml version="1.0"?> +<mavlink> + <include>common.xml</include> + + <!-- <enums> + <enum name="SLUGS_ACTION" > + <description> Slugs Actions </description> + <entry name = "SLUGS_ACTION_NONE"> + <entry name = "SLUGS_ACTION_SUCCESS"> + <entry name = "SLUGS_ACTION_FAIL"> + <entry name = "SLUGS_ACTION_EEPROM"> + <entry name = "SLUGS_ACTION_MODE_CHANGE"> + <entry name = "SLUGS_ACTION_MODE_REPORT"> + <entry name = "SLUGS_ACTION_PT_CHANGE"> + <entry name = "SLUGS_ACTION_PT_REPORT"> + <entry name = "SLUGS_ACTION_PID_CHANGE"> + <entry name = "SLUGS_ACTION_PID_REPORT"> + <entry name = "SLUGS_ACTION_WP_CHANGE"> + <entry name = "SLUGS_ACTION_WP_REPORT"> + <entry name = "SLUGS_ACTION_MLC_CHANGE"> + <entry name = "SLUGS_ACTION_MLC_REPORT"> + </enum> + + <enum name="WP_PROTOCOL_STATE" > + <description> Waypoint Protocol States </description> + <entry name = "WP_PROT_IDLE"> + <entry name = "WP_PROT_LIST_REQUESTED"> + <entry name = "WP_PROT_NUM_SENT"> + <entry name = "WP_PROT_TX_WP"> + <entry name = "WP_PROT_RX_WP"> + <entry name = "WP_PROT_SENDING_WP_IDLE"> + <entry name = "WP_PROT_GETTING_WP_IDLE"> + </enum> + +</enums> --> + + <messages> + + <message name="CPU_LOAD" id="170"> + Sensor and DSC control loads. + <field name="sensLoad" type="uint8_t">Sensor DSC Load</field> + <field name="ctrlLoad" type="uint8_t">Control DSC Load</field> + <field name="batVolt" type="uint16_t">Battery Voltage in millivolts</field> + </message> + + <message name="AIR_DATA" id="171"> + Air data for altitude and airspeed computation. + <field name="dynamicPressure" type="float">Dynamic pressure (Pa)</field> + <field name="staticPressure" type="float">Static pressure (Pa)</field> + <field name="temperature" type="uint16_t">Board temperature</field> + </message> + + <message name="SENSOR_BIAS" id="172"> + Accelerometer and gyro biases. + <field name="axBias" type="float">Accelerometer X bias (m/s)</field> + <field name="ayBias" type="float">Accelerometer Y bias (m/s)</field> + <field name="azBias" type="float">Accelerometer Z bias (m/s)</field> + <field name="gxBias" type="float">Gyro X bias (rad/s)</field> + <field name="gyBias" type="float">Gyro Y bias (rad/s)</field> + <field name="gzBias" type="float">Gyro Z bias (rad/s)</field> + </message> + + <message name="DIAGNOSTIC" id="173"> + Configurable diagnostic messages. + <field name="diagFl1" type="float">Diagnostic float 1</field> + <field name="diagFl2" type="float">Diagnostic float 2</field> + <field name="diagFl3" type="float">Diagnostic float 3</field> + <field name="diagSh1" type="int16_t">Diagnostic short 1</field> + <field name="diagSh2" type="int16_t">Diagnostic short 2</field> + <field name="diagSh3" type="int16_t">Diagnostic short 3</field> + </message> + + <message name="SLUGS_NAVIGATION" id="176"> + Data used in the navigation algorithm. + <field name="u_m" type="float">Measured Airspeed prior to the Nav Filter</field> + <field name="phi_c" type="float">Commanded Roll</field> + <field name="theta_c" type="float">Commanded Pitch</field> + <field name="psiDot_c" type="float">Commanded Turn rate</field> + <field name="ay_body" type="float">Y component of the body acceleration</field> + <field name="totalDist" type="float">Total Distance to Run on this leg of Navigation</field> + <field name="dist2Go" type="float">Remaining distance to Run on this leg of Navigation</field> + <field name="fromWP" type="uint8_t">Origin WP</field> + <field name="toWP" type="uint8_t">Destination WP</field> + </message> + + <message name="DATA_LOG" id="177"> + Configurable data log probes to be used inside Simulink + <field name="fl_1" type="float">Log value 1 </field> + <field name="fl_2" type="float">Log value 2 </field> + <field name="fl_3" type="float">Log value 3 </field> + <field name="fl_4" type="float">Log value 4 </field> + <field name="fl_5" type="float">Log value 5 </field> + <field name="fl_6" type="float">Log value 6 </field> + </message> + + <message name="GPS_DATE_TIME" id="179"> + Pilot console PWM messges. + <field name="year" type="uint8_t">Year reported by Gps </field> + <field name="month" type="uint8_t">Month reported by Gps </field> + <field name="day" type="uint8_t">Day reported by Gps </field> + <field name="hour" type="uint8_t">Hour reported by Gps </field> + <field name="min" type="uint8_t">Min reported by Gps </field> + <field name="sec" type="uint8_t">Sec reported by Gps </field> + <field name="visSat" type="uint8_t">Visible sattelites reported by Gps </field> + </message> + + <message name="MID_LVL_CMDS" id="180"> + Mid Level commands sent from the GS to the autopilot. These are only sent when being opperated in mid-level commands mode from the ground; for periodic report of these commands generated from the autopilot see message XXXX. + <field name="target" type="uint8_t">The system setting the commands</field> + <field name="hCommand" type="float">Commanded Airspeed</field> + <field name="uCommand" type="float">Log value 2 </field> + <field name="rCommand" type="float">Log value 3 </field> + </message> + + + <message name="CTRL_SRFC_PT" id="181"> + This message configures the Selective Passthrough mode. it allows to select which control surfaces the Pilot can control from his console. It is implemented as a bitfield as follows: + Position Bit Code + ================================= + 15-8 Reserved + 7 dt_pass 128 + 6 dla_pass 64 + 5 dra_pass 32 + 4 dr_pass 16 + 3 dle_pass 8 + 2 dre_pass 4 + 1 dlf_pass 2 + 0 drf_pass 1 + Where Bit 15 is the MSb. 0 = AP has control of the surface; 1 = Pilot Console has control of the surface. + <field name="target" type="uint8_t">The system setting the commands</field> + <field name="bitfieldPt" type="uint16_t">Bitfield containing the PT configuration</field> + </message> + + + + <message name="SLUGS_ACTION" id="183"> + Action messages focused on the SLUGS AP. + <field name="target" type="uint8_t">The system reporting the action</field> + <field name="actionId" type="uint8_t">Action ID. See apDefinitions.h in the SLUGS /clib directory for the ID names</field> + <field name="actionVal" type="uint16_t">Value associated with the action</field> + </message> + + </messages> +</mavlink> diff --git a/libraries/GCS_MAVLink/message_definitions/test.xml b/libraries/GCS_MAVLink/message_definitions/test.xml new file mode 100644 index 0000000000000000000000000000000000000000..43a11e3d139782e3d7b008e898c6c7891828bd0e --- /dev/null +++ b/libraries/GCS_MAVLink/message_definitions/test.xml @@ -0,0 +1,31 @@ +<?xml version='1.0'?> +<mavlink> + <version>3</version> + <messages> + <message id="0" name="TEST_TYPES"> + <description>Test all field types</description> + <field type="char" name="c">char</field> + <field type="char[10]" name="s">string</field> + <field type="uint8_t" name="u8">uint8_t</field> + <field type="uint16_t" name="u16">uint16_t</field> + <field type="uint32_t" name="u32" print_format="0x%08x">uint32_t</field> + <field type="uint64_t" name="u64">uint64_t</field> + <field type="int8_t" name="s8">int8_t</field> + <field type="int16_t" name="s16">int16_t</field> + <field type="int32_t" name="s32">int32_t</field> + <field type="int64_t" name="s64">int64_t</field> + <field type="float" name="f">float</field> + <field type="double" name="d">double</field> + <field type="uint8_t[3]" name="u8_array">uint8_t_array</field> + <field type="uint16_t[3]" name="u16_array">uint16_t_array</field> + <field type="uint32_t[3]" name="u32_array">uint32_t_array</field> + <field type="uint64_t[3]" name="u64_array">uint64_t_array</field> + <field type="int8_t[3]" name="s8_array">int8_t_array</field> + <field type="int16_t[3]" name="s16_array">int16_t_array</field> + <field type="int32_t[3]" name="s32_array">int32_t_array</field> + <field type="int64_t[3]" name="s64_array">int64_t_array</field> + <field type="float[3]" name="f_array">float_array</field> + <field type="double[3]" name="d_array">double_array</field> + </message> + </messages> +</mavlink> diff --git a/libraries/GCS_MAVLink/message_definitions/ualberta.xml b/libraries/GCS_MAVLink/message_definitions/ualberta.xml new file mode 100644 index 0000000000000000000000000000000000000000..5e53e141e9f018e943abfd25bc1f58c0a0091574 --- /dev/null +++ b/libraries/GCS_MAVLink/message_definitions/ualberta.xml @@ -0,0 +1,54 @@ +<?xml version='1.0'?> +<mavlink> + <include>common.xml</include> + <enums> + <enum name="UALBERTA_AUTOPILOT_MODE"> + <description>Available autopilot modes for ualberta uav</description> + <entry name="MODE_MANUAL_DIRECT">Raw input pulse widts sent to output</entry> + <entry name="MODE_MANUAL_SCALED">Inputs are normalized using calibration, the converted back to raw pulse widths for output</entry> + <entry name="MODE_AUTO_PID_ATT"> dfsdfs</entry> + <entry name="MODE_AUTO_PID_VEL"> dfsfds</entry> + <entry name="MODE_AUTO_PID_POS"> dfsdfsdfs</entry> + </enum> + <enum name="UALBERTA_NAV_MODE"> + <description>Navigation filter mode</description> + <entry name="NAV_AHRS_INIT" /> + <entry name="NAV_AHRS">AHRS mode</entry> + <entry name="NAV_INS_GPS_INIT">INS/GPS initialization mode</entry> + <entry name="NAV_INS_GPS">INS/GPS mode</entry> + </enum> + <enum name="UALBERTA_PILOT_MODE"> + <description>Mode currently commanded by pilot</description> + <entry name="PILOT_MANUAL"> sdf</entry> + <entry name="PILOT_AUTO"> dfs</entry> + <entry name="PILOT_ROTO"> Rotomotion mode </entry> + </enum> + </enums> + <messages> + <message id="220" name="NAV_FILTER_BIAS"> + <description>Accelerometer and Gyro biases from the navigation filter</description> + <field type="uint64_t" name="usec">Timestamp (microseconds)</field> + <field type="float" name="accel_0">b_f[0]</field> + <field type="float" name="accel_1">b_f[1]</field> + <field type="float" name="accel_2">b_f[2]</field> + <field type="float" name="gyro_0">b_f[0]</field> + <field type="float" name="gyro_1">b_f[1]</field> + <field type="float" name="gyro_2">b_f[2]</field> + </message> + <message id="221" name="RADIO_CALIBRATION"> + <description>Complete set of calibration parameters for the radio</description> + <field type="uint16_t[3]" name="aileron">Aileron setpoints: left, center, right</field> + <field type="uint16_t[3]" name="elevator">Elevator setpoints: nose down, center, nose up</field> + <field type="uint16_t[3]" name="rudder">Rudder setpoints: nose left, center, nose right</field> + <field type="uint16_t[2]" name="gyro">Tail gyro mode/gain setpoints: heading hold, rate mode</field> + <field type="uint16_t[5]" name="pitch">Pitch curve setpoints (every 25%)</field> + <field type="uint16_t[5]" name="throttle">Throttle curve setpoints (every 25%)</field> + </message> + <message id="222" name="UALBERTA_SYS_STATUS"> + <description>System status specific to ualberta uav</description> + <field type="uint8_t" name="mode">System mode, see UALBERTA_AUTOPILOT_MODE ENUM</field> + <field type="uint8_t" name="nav_mode">Navigation mode, see UALBERTA_NAV_MODE ENUM</field> + <field type="uint8_t" name="pilot">Pilot mode, see UALBERTA_PILOT_MODE</field> + </message> + </messages> +</mavlink> diff --git a/libraries/GCS_MAVLink/message_definitions_v1.0/ardupilotmega.xml b/libraries/GCS_MAVLink/message_definitions_v1.0/ardupilotmega.xml new file mode 100644 index 0000000000000000000000000000000000000000..618b9bc24c347a2ce65c3e199c31c6bb6e1784e6 --- /dev/null +++ b/libraries/GCS_MAVLink/message_definitions_v1.0/ardupilotmega.xml @@ -0,0 +1,270 @@ +<?xml version='1.0'?> +<mavlink> + <include>common.xml</include> + <!-- note that APM specific messages should use the command id + range from 150 to 250, to leave plenty of room for growth + of common.xml + + If you prototype a message here, then you should consider if it + is general enough to move into common.xml later + --> + + + <enums> + <!-- Camera Mount mode Enumeration --> + <enum name="MAV_MOUNT_MODE"> + <description>Enumeration of possible mount operation modes</description> + <entry name="MAV_MOUNT_MODE_RETRACT" value="0"><description>Load and keep safe position (Roll,Pitch,Yaw) from EEPROM and stop stabilization</description></entry> + <entry name="MAV_MOUNT_MODE_NEUTRAL" value="1"><description>Load and keep neutral position (Roll,Pitch,Yaw) from EEPROM.</description></entry> + <entry name="MAV_MOUNT_MODE_MAVLINK_TARGETING" value="2"><description>Load neutral position and start MAVLink Roll,Pitch,Yaw control with stabilization</description></entry> + <entry name="MAV_MOUNT_MODE_RC_TARGETING" value="3"><description>Load neutral position and start RC Roll,Pitch,Yaw control with stabilization</description></entry> + <entry name="MAV_MOUNT_MODE_GPS_POINT" value="4"><description>Load neutral position and start to point to Lat,Lon,Alt</description></entry> + </enum> + + <enum name="MAV_CMD" > + <!-- Camera Controller Mission Commands Enumeration --> + <entry name="MAV_CMD_DO_DIGICAM_CONFIGURE" value="202"> + <description>Mission command to configure an on-board camera controller system.</description> + <param index="1">Modes: P, TV, AV, M, Etc</param> + <param index="2">Shutter speed: Divisor number for one second</param> + <param index="3">Aperture: F stop number</param> + <param index="4">ISO number e.g. 80, 100, 200, Etc</param> + <param index="5">Exposure type enumerator</param> + <param index="6">Command Identity</param> + <param index="7">Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off)</param> + </entry> + + <entry name="MAV_CMD_DO_DIGICAM_CONTROL" value="203"> + <description>Mission command to control an on-board camera controller system.</description> + <param index="1">Session control e.g. show/hide lens</param> + <param index="2">Zoom's absolute position</param> + <param index="3">Zooming step value to offset zoom from the current position</param> + <param index="4">Focus Locking, Unlocking or Re-locking</param> + <param index="5">Shooting Command</param> + <param index="6">Command Identity</param> + <param index="7">Empty</param> + </entry> + + <!-- Camera Mount Mission Commands Enumeration --> + <entry name="MAV_CMD_DO_MOUNT_CONFIGURE" value="204"> + <description>Mission command to configure a camera or antenna mount</description> + <param index="1">Mount operation mode (see MAV_MOUNT_MODE enum)</param> + <param index="2">stabilize roll? (1 = yes, 0 = no)</param> + <param index="3">stabilize pitch? (1 = yes, 0 = no)</param> + <param index="4">stabilize yaw? (1 = yes, 0 = no)</param> + <param index="5">Empty</param> + <param index="6">Empty</param> + <param index="7">Empty</param> + </entry> + + <entry name="MAV_CMD_DO_MOUNT_CONTROL" value="205"> + <description>Mission command to control a camera or antenna mount</description> + <param index="1">pitch(deg*100) or lat, depending on mount mode.</param> + <param index="2">roll(deg*100) or lon depending on mount mode</param> + <param index="3">yaw(deg*100) or alt (in cm) depending on mount mode</param> + <param index="4">Empty</param> + <param index="5">Empty</param> + <param index="6">Empty</param> + <param index="7">Empty</param> + </entry> + </enum> + + <!-- fenced mode enums --> + <enum name="FENCE_ACTION"> + <entry name="FENCE_ACTION_NONE" value="0"> + <description>Disable fenced mode</description> + </entry> + <entry name="FENCE_ACTION_GUIDED" value="1"> + <description>Switched to guided mode to return point (fence point 0)</description> + </entry> + </enum> + + <enum name="FENCE_BREACH"> + <entry name="FENCE_BREACH_NONE" value="0"> + <description>No last fence breach</description> + </entry> + <entry name="FENCE_BREACH_MINALT" value="1"> + <description>Breached minimum altitude</description> + </entry> + <entry name="FENCE_BREACH_MAXALT" value="2"> + <description>Breached minimum altitude</description> + </entry> + <entry name="FENCE_BREACH_BOUNDARY" value="3"> + <description>Breached fence boundary</description> + </entry> + </enum> + </enums> + + <messages> + <message id="150" name="SENSOR_OFFSETS"> + <description>Offsets and calibrations values for hardware + sensors. This makes it easier to debug the calibration process.</description> + <field type="int16_t" name="mag_ofs_x">magnetometer X offset</field> + <field type="int16_t" name="mag_ofs_y">magnetometer Y offset</field> + <field type="int16_t" name="mag_ofs_z">magnetometer Z offset</field> + <field type="float" name="mag_declination">magnetic declination (radians)</field> + <field type="int32_t" name="raw_press">raw pressure from barometer</field> + <field type="int32_t" name="raw_temp">raw temperature from barometer</field> + <field type="float" name="gyro_cal_x">gyro X calibration</field> + <field type="float" name="gyro_cal_y">gyro Y calibration</field> + <field type="float" name="gyro_cal_z">gyro Z calibration</field> + <field type="float" name="accel_cal_x">accel X calibration</field> + <field type="float" name="accel_cal_y">accel Y calibration</field> + <field type="float" name="accel_cal_z">accel Z calibration</field> + </message> + + <message id="151" name="SET_MAG_OFFSETS"> + <description>set the magnetometer offsets</description> + <field type="uint8_t" name="target_system">System ID</field> + <field type="uint8_t" name="target_component">Component ID</field> + <field type="int16_t" name="mag_ofs_x">magnetometer X offset</field> + <field type="int16_t" name="mag_ofs_y">magnetometer Y offset</field> + <field type="int16_t" name="mag_ofs_z">magnetometer Z offset</field> + </message> + + <message id="152" name="MEMINFO"> + <description>state of APM memory</description> + <field type="uint16_t" name="brkval">heap top</field> + <field type="uint16_t" name="freemem">free memory</field> + </message> + + <message id="153" name="AP_ADC"> + <description>raw ADC output</description> + <field type="uint16_t" name="adc1">ADC output 1</field> + <field type="uint16_t" name="adc2">ADC output 2</field> + <field type="uint16_t" name="adc3">ADC output 3</field> + <field type="uint16_t" name="adc4">ADC output 4</field> + <field type="uint16_t" name="adc5">ADC output 5</field> + <field type="uint16_t" name="adc6">ADC output 6</field> + </message> + + <!-- Camera Controller Messages --> + <message name="DIGICAM_CONFIGURE" id="154"> + <description>Configure on-board Camera Control System.</description> + <field name="target_system" type="uint8_t">System ID</field> + <field name="target_component" type="uint8_t">Component ID</field> + <field name="mode" type="uint8_t">Mode enumeration from 1 to N //P, TV, AV, M, Etc (0 means ignore)</field> + <field name="shutter_speed" type="uint16_t">Divisor number //e.g. 1000 means 1/1000 (0 means ignore)</field> + <field name="aperture" type="uint8_t">F stop number x 10 //e.g. 28 means 2.8 (0 means ignore)</field> + <field name="iso" type="uint8_t">ISO enumeration from 1 to N //e.g. 80, 100, 200, Etc (0 means ignore)</field> + <field name="exposure_type" type="uint8_t">Exposure type enumeration from 1 to N (0 means ignore)</field> + <field name="command_id" type="uint8_t">Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once</field> + <field name="engine_cut_off" type="uint8_t">Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off)</field> + <field name="extra_param" type="uint8_t">Extra parameters enumeration (0 means ignore)</field> + <field name="extra_value" type="float">Correspondent value to given extra_param</field> + </message> + + <message name="DIGICAM_CONTROL" id="155"> + <description>Control on-board Camera Control System to take shots.</description> + <field name="target_system" type="uint8_t">System ID</field> + <field name="target_component" type="uint8_t">Component ID</field> + <field name="session" type="uint8_t">0: stop, 1: start or keep it up //Session control e.g. show/hide lens</field> + <field name="zoom_pos" type="uint8_t">1 to N //Zoom's absolute position (0 means ignore)</field> + <field name="zoom_step" type="int8_t">-100 to 100 //Zooming step value to offset zoom from the current position</field> + <field name="focus_lock" type="uint8_t">0: unlock focus or keep unlocked, 1: lock focus or keep locked, 3: re-lock focus</field> + <field name="shot" type="uint8_t">0: ignore, 1: shot or start filming</field> + <field name="command_id" type="uint8_t">Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once</field> + <field name="extra_param" type="uint8_t">Extra parameters enumeration (0 means ignore)</field> + <field name="extra_value" type="float">Correspondent value to given extra_param</field> + </message> + + <!-- Camera Mount Messages --> + <message name="MOUNT_CONFIGURE" id="156"> + <description>Message to configure a camera mount, directional antenna, etc.</description> + <field name="target_system" type="uint8_t">System ID</field> + <field name="target_component" type="uint8_t">Component ID</field> + <field name="mount_mode" type="uint8_t">mount operating mode (see MAV_MOUNT_MODE enum)</field> + <field name="stab_roll" type="uint8_t">(1 = yes, 0 = no)</field> + <field name="stab_pitch" type="uint8_t">(1 = yes, 0 = no)</field> + <field name="stab_yaw" type="uint8_t">(1 = yes, 0 = no)</field> + </message> + + <message name="MOUNT_CONTROL" id="157"> + <description>Message to control a camera mount, directional antenna, etc.</description> + <field name="target_system" type="uint8_t">System ID</field> + <field name="target_component" type="uint8_t">Component ID</field> + <field name="input_a" type="int32_t">pitch(deg*100) or lat, depending on mount mode</field> + <field name="input_b" type="int32_t">roll(deg*100) or lon depending on mount mode</field> + <field name="input_c" type="int32_t">yaw(deg*100) or alt (in cm) depending on mount mode</field> + <field name="save_position" type="uint8_t">if "1" it will save current trimmed position on EEPROM (just valid for NEUTRAL and LANDING)</field> + </message> + + <message name="MOUNT_STATUS" id="158"> + <description>Message with some status from APM to GCS about camera or antenna mount</description> + <field name="target_system" type="uint8_t">System ID</field> + <field name="target_component" type="uint8_t">Component ID</field> + <field name="pointing_a" type="int32_t">pitch(deg*100) or lat, depending on mount mode</field> + <field name="pointing_b" type="int32_t">roll(deg*100) or lon depending on mount mode</field> + <field name="pointing_c" type="int32_t">yaw(deg*100) or alt (in cm) depending on mount mode</field> + </message> + + <!-- geo-fence messages --> + <message name="FENCE_POINT" id="160"> + <description>A fence point. Used to set a point when from + GCS -> MAV. Also used to return a point from MAV -> GCS</description> + <field name="target_system" type="uint8_t">System ID</field> + <field name="target_component" type="uint8_t">Component ID</field> + <field name="idx" type="uint8_t">point index (first point is 1, 0 is for return point)</field> + <field name="count" type="uint8_t">total number of points (for sanity checking)</field> + <field name="lat" type="float">Latitude of point</field> + <field name="lng" type="float">Longitude of point</field> + </message> + + <message name="FENCE_FETCH_POINT" id="161"> + <description>Request a current fence point from MAV</description> + <field name="target_system" type="uint8_t">System ID</field> + <field name="target_component" type="uint8_t">Component ID</field> + <field name="idx" type="uint8_t">point index (first point is 1, 0 is for return point)</field> + </message> + + <message name="FENCE_STATUS" id="162"> + <description>Status of geo-fencing. Sent in extended + status stream when fencing enabled</description> + <field name="breach_status" type="uint8_t">0 if currently inside fence, 1 if outside</field> + <field name="breach_count" type="uint16_t">number of fence breaches</field> + <field name="breach_type" type="uint8_t">last breach type (see FENCE_BREACH_* enum)</field> + <field name="breach_time" type="uint32_t">time of last breach in milliseconds since boot</field> + </message> + + <message name="AHRS" id="163"> + <description>Status of DCM attitude estimator</description> + <field type="float" name="omegaIx">X gyro drift estimate rad/s</field> + <field type="float" name="omegaIy">Y gyro drift estimate rad/s</field> + <field type="float" name="omegaIz">Z gyro drift estimate rad/s</field> + <field type="float" name="accel_weight">average accel_weight</field> + <field type="float" name="renorm_val">average renormalisation value</field> + <field type="float" name="error_rp">average error_roll_pitch value</field> + <field type="float" name="error_yaw">average error_yaw value</field> + </message> + + <message name="SIMSTATE" id="164"> + <description>Status of simulation environment, if used</description> + <field type="float" name="roll">Roll angle (rad)</field> + <field type="float" name="pitch">Pitch angle (rad)</field> + <field type="float" name="yaw">Yaw angle (rad)</field> + <field type="float" name="xacc">X acceleration m/s/s</field> + <field type="float" name="yacc">Y acceleration m/s/s</field> + <field type="float" name="zacc">Z acceleration m/s/s</field> + <field type="float" name="xgyro">Angular speed around X axis rad/s</field> + <field type="float" name="ygyro">Angular speed around Y axis rad/s</field> + <field type="float" name="zgyro">Angular speed around Z axis rad/s</field> + </message> + + <message name="HWSTATUS" id="165"> + <description>Status of key hardware</description> + <field type="uint16_t" name="Vcc">board voltage (mV)</field> + <field type="uint8_t" name="I2Cerr">I2C error count</field> + </message> + + <message name="RADIO" id="166"> + <description>Status generated by radio</description> + <field type="uint8_t" name="rssi">local signal strength</field> + <field type="uint8_t" name="remrssi">remote signal strength</field> + <field type="uint8_t" name="txbuf">how full the tx buffer is as a percentage</field> + <field type="uint8_t" name="noise">background noise level</field> + <field type="uint8_t" name="remnoise">remote background noise level</field> + <field type="uint16_t" name="rxerrors">receive errors</field> + <field type="uint16_t" name="fixed">count of error corrected packets</field> + </message> + </messages> +</mavlink> diff --git a/libraries/GCS_MAVLink/message_definitions_v1.0/common.xml b/libraries/GCS_MAVLink/message_definitions_v1.0/common.xml new file mode 100644 index 0000000000000000000000000000000000000000..26653be7ec9bed719874847fd267145c1fb79e7f --- /dev/null +++ b/libraries/GCS_MAVLink/message_definitions_v1.0/common.xml @@ -0,0 +1,1531 @@ +<?xml version='1.0'?> +<mavlink> + <version>3</version> + <enums> + <enum name="MAV_AUTOPILOT"> + <description>Micro air vehicle / autopilot classes. This identifies the individual model.</description> + <entry value="0" name="MAV_AUTOPILOT_GENERIC"> + <description>Generic autopilot, full support for everything</description> + </entry> + <entry value="1" name="MAV_AUTOPILOT_PIXHAWK"> + <description>PIXHAWK autopilot, http://pixhawk.ethz.ch</description> + </entry> + <entry value="2" name="MAV_AUTOPILOT_SLUGS"> + <description>SLUGS autopilot, http://slugsuav.soe.ucsc.edu</description> + </entry> + <entry value="3" name="MAV_AUTOPILOT_ARDUPILOTMEGA"> + <description>ArduPilotMega / ArduCopter, http://diydrones.com</description> + </entry> + <entry value="4" name="MAV_AUTOPILOT_OPENPILOT"> + <description>OpenPilot, http://openpilot.org</description> + </entry> + <entry value="5" name="MAV_AUTOPILOT_GENERIC_WAYPOINTS_ONLY"> + <description>Generic autopilot only supporting simple waypoints</description> + </entry> + <entry value="6" name="MAV_AUTOPILOT_GENERIC_WAYPOINTS_AND_SIMPLE_NAVIGATION_ONLY"> + <description>Generic autopilot supporting waypoints and other simple navigation commands</description> + </entry> + <entry value="7" name="MAV_AUTOPILOT_GENERIC_MISSION_FULL"> + <description>Generic autopilot supporting the full mission command set</description> + </entry> + <entry value="8" name="MAV_AUTOPILOT_INVALID"> + <description>No valid autopilot, e.g. a GCS or other MAVLink component</description> + </entry> + <entry value="9" name="MAV_AUTOPILOT_PPZ"> + <description>PPZ UAV - http://nongnu.org/paparazzi</description> + </entry> + <entry value="10" name="MAV_AUTOPILOT_UDB"> + <description>UAV Dev Board</description> + </entry> + <entry value="11" name="MAV_AUTOPILOT_FP"> + <description>FlexiPilot</description> + </entry> + </enum> + <enum name="MAV_TYPE"> + <entry value="0" name="MAV_TYPE_GENERIC"> + <description>Generic micro air vehicle.</description> + </entry> + <entry value="1" name="MAV_TYPE_FIXED_WING"> + <description>Fixed wing aircraft.</description> + </entry> + <entry value="2" name="MAV_TYPE_QUADROTOR"> + <description>Quadrotor</description> + </entry> + <entry value="3" name="MAV_TYPE_COAXIAL"> + <description>Coaxial helicopter</description> + </entry> + <entry value="4" name="MAV_TYPE_HELICOPTER"> + <description>Normal helicopter with tail rotor.</description> + </entry> + <entry value="5" name="MAV_TYPE_ANTENNA_TRACKER"> + <description>Ground installation</description> + </entry> + <entry value="6" name="MAV_TYPE_GCS"> + <description>Operator control unit / ground control station</description> + </entry> + <entry value="7" name="MAV_TYPE_AIRSHIP"> + <description>Airship, controlled</description> + </entry> + <entry value="8" name="MAV_TYPE_FREE_BALLOON"> + <description>Free balloon, uncontrolled</description> + </entry> + <entry value="9" name="MAV_TYPE_ROCKET"> + <description>Rocket</description> + </entry> + <entry value="10" name="MAV_TYPE_GROUND_ROVER"> + <description>Ground rover</description> + </entry> + <entry value="11" name="MAV_TYPE_SURFACE_BOAT"> + <description>Surface vessel, boat, ship</description> + </entry> + <entry value="12" name="MAV_TYPE_SUBMARINE"> + <description>Submarine</description> + </entry> + <entry value="13" name="MAV_TYPE_HEXAROTOR"> + <description>Hexarotor</description> + </entry> + <entry value="14" name="MAV_TYPE_OCTOROTOR"> + <description>Octorotor</description> + </entry> + <entry value="15" name="MAV_TYPE_TRICOPTER"> + <description>Octorotor</description> + </entry> + <entry value="16" name="MAV_TYPE_FLAPPING_WING"> + <description>Flapping wing</description> + </entry> + </enum> + <!-- WARNING: MAV_ACTION Enum is no longer supported - has been removed. Please use MAV_CMD --> + <enum name="MAV_MODE_FLAG"> + <description>These flags encode the MAV mode.</description> + <entry value="128" name="MAV_MODE_FLAG_SAFETY_ARMED"> + <description>0b10000000 MAV safety set to armed. Motors are enabled / running / can start. Ready to fly.</description> + </entry> + <entry value="64" name="MAV_MODE_FLAG_MANUAL_INPUT_ENABLED"> + <description>0b01000000 remote control input is enabled.</description> + </entry> + <entry value="32" name="MAV_MODE_FLAG_HIL_ENABLED"> + <description>0b00100000 hardware in the loop simulation. All motors / actuators are blocked, but internal software is full operational.</description> + </entry> + <entry value="16" name="MAV_MODE_FLAG_STABILIZE_ENABLED"> + <description>0b00010000 system stabilizes electronically its attitude (and optionally position). It needs however further control inputs to move around.</description> + </entry> + <entry value="8" name="MAV_MODE_FLAG_GUIDED_ENABLED"> + <description>0b00001000 guided mode enabled, system flies MISSIONs / mission items.</description> + </entry> + <entry value="4" name="MAV_MODE_FLAG_AUTO_ENABLED"> + <description>0b00000100 autonomous mode enabled, system finds its own goal positions. Guided flag can be set or not, depends on the actual implementation.</description> + </entry> + <entry value="2" name="MAV_MODE_FLAG_TEST_ENABLED"> + <description>0b00000010 system has a test mode enabled. This flag is intended for temporary system tests and should not be used for stable implementations.</description> + </entry> + <entry value="1" name="MAV_MODE_FLAG_CUSTOM_MODE_ENABLED"> + <description>0b00000001 Reserved for future use.</description> + </entry> + </enum> + <enum name="MAV_MODE_FLAG_DECODE_POSITION"> + <description>These values encode the bit positions of the decode position. These values can be used to read the value of a flag bit by combining the base_mode variable with AND with the flag position value. The result will be either 0 or 1, depending on if the flag is set or not.</description> + <entry value="128" name="MAV_MODE_FLAG_DECODE_POSITION_SAFETY"> + <description>First bit: 10000000</description> + </entry> + <entry value="64" name="MAV_MODE_FLAG_DECODE_POSITION_MANUAL"> + <description>Second bit: 01000000</description> + </entry> + <entry value="32" name="MAV_MODE_FLAG_DECODE_POSITION_HIL"> + <description>Third bit: 00100000</description> + </entry> + <entry value="16" name="MAV_MODE_FLAG_DECODE_POSITION_STABILIZE"> + <description>Fourth bit: 00010000</description> + </entry> + <entry value="8" name="MAV_MODE_FLAG_DECODE_POSITION_GUIDED"> + <description>Fifth bit: 00001000</description> + </entry> + <entry value="4" name="MAV_MODE_FLAG_DECODE_POSITION_AUTO"> + <description>Sixt bit: 00000100</description> + </entry> + <entry value="2" name="MAV_MODE_FLAG_DECODE_POSITION_TEST"> + <description>Seventh bit: 00000010</description> + </entry> + <entry value="1" name="MAV_MODE_FLAG_DECODE_POSITION_CUSTOM_MODE"> + <description>Eighth bit: 00000001</description> + </entry> + </enum> + <enum name="MAV_GOTO"> + <description>Override command, pauses current mission execution and moves immediately to a position</description> + <entry value="0" name="MAV_GOTO_DO_HOLD"> + <description>Hold at the current position.</description> + </entry> + <entry value="1" name="MAV_GOTO_DO_CONTINUE"> + <description>Continue with the next item in mission execution.</description> + </entry> + <entry value="2" name="MAV_GOTO_HOLD_AT_CURRENT_POSITION"> + <description>Hold at the current position of the system</description> + </entry> + <entry value="3" name="MAV_GOTO_HOLD_AT_SPECIFIED_POSITION"> + <description>Hold at the position specified in the parameters of the DO_HOLD action</description> + </entry> + </enum> + <enum name="MAV_MODE"> + <description>These defines are predefined OR-combined mode flags. There is no need to use values from this enum, but it + simplifies the use of the mode flags. Note that manual input is enabled in all modes as a safety override.</description> + <entry value="0" name="MAV_MODE_PREFLIGHT"> + <description>System is not ready to fly, booting, calibrating, etc. No flag is set.</description> + </entry> + <entry value="80" name="MAV_MODE_STABILIZE_DISARMED"> + <description>System is allowed to be active, under assisted RC control.</description> + </entry> + <entry value="208" name="MAV_MODE_STABILIZE_ARMED"> + <description>System is allowed to be active, under assisted RC control.</description> + </entry> + <entry value="64" name="MAV_MODE_MANUAL_DISARMED"> + <description>System is allowed to be active, under manual (RC) control, no stabilization</description> + </entry> + <entry value="192" name="MAV_MODE_MANUAL_ARMED"> + <description>System is allowed to be active, under manual (RC) control, no stabilization</description> + </entry> + <entry value="88" name="MAV_MODE_GUIDED_DISARMED"> + <description>System is allowed to be active, under autonomous control, manual setpoint</description> + </entry> + <entry value="216" name="MAV_MODE_GUIDED_ARMED"> + <description>System is allowed to be active, under autonomous control, manual setpoint</description> + </entry> + <entry value="92" name="MAV_MODE_AUTO_DISARMED"> + <description>System is allowed to be active, under autonomous control and navigation (the trajectory is decided onboard and not pre-programmed by MISSIONs)</description> + </entry> + <entry value="220" name="MAV_MODE_AUTO_ARMED"> + <description>System is allowed to be active, under autonomous control and navigation (the trajectory is decided onboard and not pre-programmed by MISSIONs)</description> + </entry> + <entry value="66" name="MAV_MODE_TEST_DISARMED"> + <description>UNDEFINED mode. This solely depends on the autopilot - use with caution, intended for developers only.</description> + </entry> + <entry value="194" name="MAV_MODE_TEST_ARMED"> + <description>UNDEFINED mode. This solely depends on the autopilot - use with caution, intended for developers only.</description> + </entry> + </enum> + <enum name="MAV_STATE"> + <entry value="0" name="MAV_STATE_UNINIT"> + <description>Uninitialized system, state is unknown.</description> + </entry> + <entry name="MAV_STATE_BOOT"> + <description>System is booting up.</description> + </entry> + <entry name="MAV_STATE_CALIBRATING"> + <description>System is calibrating and not flight-ready.</description> + </entry> + <entry name="MAV_STATE_STANDBY"> + <description>System is grounded and on standby. It can be launched any time.</description> + </entry> + <entry name="MAV_STATE_ACTIVE"> + <description>System is active and might be already airborne. Motors are engaged.</description> + </entry> + <entry name="MAV_STATE_CRITICAL"> + <description>System is in a non-normal flight mode. It can however still navigate.</description> + </entry> + <entry name="MAV_STATE_EMERGENCY"> + <description>System is in a non-normal flight mode. It lost control over parts or over the whole airframe. It is in mayday and going down.</description> + </entry> + <entry name="MAV_STATE_POWEROFF"> + <description>System just initialized its power-down sequence, will shut down now.</description> + </entry> + </enum> + <enum name="MAV_COMPONENT"> + <entry value="0" name="MAV_COMP_ID_ALL"> + <description/> + </entry> + <entry value="220" name="MAV_COMP_ID_GPS"> + <description/> + </entry> + <entry value="190" name="MAV_COMP_ID_MISSIONPLANNER"> + <description/> + </entry> + <entry value="195" name="MAV_COMP_ID_PATHPLANNER"> + <description/> + </entry> + <entry value="180" name="MAV_COMP_ID_MAPPER"> + <description/> + </entry> + <entry value="100" name="MAV_COMP_ID_CAMERA"> + <description/> + </entry> + <entry value="200" name="MAV_COMP_ID_IMU"> + <description/> + </entry> + <entry value="201" name="MAV_COMP_ID_IMU_2"> + <description/> + </entry> + <entry value="202" name="MAV_COMP_ID_IMU_3"> + <description/> + </entry> + <entry value="240" name="MAV_COMP_ID_UDP_BRIDGE"> + <description/> + </entry> + <entry value="241" name="MAV_COMP_ID_UART_BRIDGE"> + <description/> + </entry> + <entry value="250" name="MAV_COMP_ID_SYSTEM_CONTROL"> + <description/> + </entry> + <entry value="140" name="MAV_COMP_ID_SERVO1"> + <description/> + </entry> + <entry value="141" name="MAV_COMP_ID_SERVO2"> + <description/> + </entry> + <entry value="142" name="MAV_COMP_ID_SERVO3"> + <description/> + </entry> + <entry value="143" name="MAV_COMP_ID_SERVO4"> + <description/> + </entry> + <entry value="144" name="MAV_COMP_ID_SERVO5"> + <description/> + </entry> + <entry value="145" name="MAV_COMP_ID_SERVO6"> + <description/> + </entry> + <entry value="146" name="MAV_COMP_ID_SERVO7"> + <description/> + </entry> + <entry value="147" name="MAV_COMP_ID_SERVO8"> + <description/> + </entry> + <entry value="148" name="MAV_COMP_ID_SERVO9"> + <description/> + </entry> + <entry value="149" name="MAV_COMP_ID_SERVO10"> + <description/> + </entry> + <entry value="150" name="MAV_COMP_ID_SERVO11"> + <description/> + </entry> + <entry value="151" name="MAV_COMP_ID_SERVO12"> + <description/> + </entry> + <entry value="152" name="MAV_COMP_ID_SERVO13"> + <description/> + </entry> + <entry value="153" name="MAV_COMP_ID_SERVO14"> + <description/> + </entry> + </enum> + <enum name="MAV_FRAME"> + <entry value="0" name="MAV_FRAME_GLOBAL"> + <description>Global coordinate frame, WGS84 coordinate system. First value / x: latitude, second value / y: longitude, third value / z: positive altitude over mean sea level (MSL)</description> + </entry> + <entry value="1" name="MAV_FRAME_LOCAL_NED"> + <description>Local coordinate frame, Z-up (x: north, y: east, z: down).</description> + </entry> + <entry value="2" name="MAV_FRAME_MISSION"> + <description>NOT a coordinate frame, indicates a mission command.</description> + </entry> + <entry value="3" name="MAV_FRAME_GLOBAL_RELATIVE_ALT"> + <description>Global coordinate frame, WGS84 coordinate system, relative altitude over ground with respect to the home position. First value / x: latitude, second value / y: longitude, third value / z: positive altitude with 0 being at the altitude of the home location.</description> + </entry> + <entry value="4" name="MAV_FRAME_LOCAL_ENU"> + <description>Local coordinate frame, Z-down (x: east, y: north, z: up)</description> + </entry> + </enum> + <enum name="MAVLINK_DATA_STREAM_TYPE"> + <entry name="MAVLINK_DATA_STREAM_IMG_JPEG"> + <description/> + </entry> + <entry name="MAVLINK_DATA_STREAM_IMG_BMP"> + <description/> + </entry> + <entry name="MAVLINK_DATA_STREAM_IMG_RAW8U"> + <description/> + </entry> + <entry name="MAVLINK_DATA_STREAM_IMG_RAW32U"> + <description/> + </entry> + <entry name="MAVLINK_DATA_STREAM_IMG_PGM"> + <description/> + </entry> + <entry name="MAVLINK_DATA_STREAM_IMG_PNG"> + <description/> + </entry> + </enum> + <enum name="MAV_CMD"> + <description>Commands to be executed by the MAV. They can be executed on user request, or as part of a mission script. If the action is used in a mission, the parameter mapping to the waypoint/mission message is as follows: Param 1, Param 2, Param 3, Param 4, X: Param 5, Y:Param 6, Z:Param 7. This command list is similar what ARINC 424 is for commercial aircraft: A data format how to interpret waypoint/mission data.</description> + <entry value="16" name="MAV_CMD_NAV_WAYPOINT"> + <description>Navigate to MISSION.</description> + <param index="1">Hold time in decimal seconds. (ignored by fixed wing, time to stay at MISSION for rotary wing)</param> + <param index="2">Acceptance radius in meters (if the sphere with this radius is hit, the MISSION counts as reached)</param> + <param index="3">0 to pass through the WP, if > 0 radius in meters to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control.</param> + <param index="4">Desired yaw angle at MISSION (rotary wing)</param> + <param index="5">Latitude</param> + <param index="6">Longitude</param> + <param index="7">Altitude</param> + </entry> + <entry value="17" name="MAV_CMD_NAV_LOITER_UNLIM"> + <description>Loiter around this MISSION an unlimited amount of time</description> + <param index="1">Empty</param> + <param index="2">Empty</param> + <param index="3">Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise</param> + <param index="4">Desired yaw angle.</param> + <param index="5">Latitude</param> + <param index="6">Longitude</param> + <param index="7">Altitude</param> + </entry> + <entry value="18" name="MAV_CMD_NAV_LOITER_TURNS"> + <description>Loiter around this MISSION for X turns</description> + <param index="1">Turns</param> + <param index="2">Empty</param> + <param index="3">Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise</param> + <param index="4">Desired yaw angle.</param> + <param index="5">Latitude</param> + <param index="6">Longitude</param> + <param index="7">Altitude</param> + </entry> + <entry value="19" name="MAV_CMD_NAV_LOITER_TIME"> + <description>Loiter around this MISSION for X seconds</description> + <param index="1">Seconds (decimal)</param> + <param index="2">Empty</param> + <param index="3">Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise</param> + <param index="4">Desired yaw angle.</param> + <param index="5">Latitude</param> + <param index="6">Longitude</param> + <param index="7">Altitude</param> + </entry> + <entry value="20" name="MAV_CMD_NAV_RETURN_TO_LAUNCH"> + <description>Return to launch location</description> + <param index="1">Empty</param> + <param index="2">Empty</param> + <param index="3">Empty</param> + <param index="4">Empty</param> + <param index="5">Empty</param> + <param index="6">Empty</param> + <param index="7">Empty</param> + </entry> + <entry value="21" name="MAV_CMD_NAV_LAND"> + <description>Land at location</description> + <param index="1">Empty</param> + <param index="2">Empty</param> + <param index="3">Empty</param> + <param index="4">Desired yaw angle.</param> + <param index="5">Latitude</param> + <param index="6">Longitude</param> + <param index="7">Altitude</param> + </entry> + <entry value="22" name="MAV_CMD_NAV_TAKEOFF"> + <description>Takeoff from ground / hand</description> + <param index="1">Minimum pitch (if airspeed sensor present), desired pitch without sensor</param> + <param index="2">Empty</param> + <param index="3">Empty</param> + <param index="4">Yaw angle (if magnetometer present), ignored without magnetometer</param> + <param index="5">Latitude</param> + <param index="6">Longitude</param> + <param index="7">Altitude</param> + </entry> + <entry value="80" name="MAV_CMD_NAV_ROI"> + <description>Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras.</description> + <param index="1">Region of intereset mode. (see MAV_ROI enum)</param> + <param index="2">MISSION index/ target ID. (see MAV_ROI enum)</param> + <param index="3">ROI index (allows a vehicle to manage multiple ROI's)</param> + <param index="4">Empty</param> + <param index="5">x the location of the fixed ROI (see MAV_FRAME)</param> + <param index="6">y</param> + <param index="7">z</param> + </entry> + <entry value="81" name="MAV_CMD_NAV_PATHPLANNING"> + <description>Control autonomous path planning on the MAV.</description> + <param index="1">0: Disable local obstacle avoidance / local path planning (without resetting map), 1: Enable local path planning, 2: Enable and reset local path planning</param> + <param index="2">0: Disable full path planning (without resetting map), 1: Enable, 2: Enable and reset map/occupancy grid, 3: Enable and reset planned route, but not occupancy grid</param> + <param index="3">Empty</param> + <param index="4">Yaw angle at goal, in compass degrees, [0..360]</param> + <param index="5">Latitude/X of goal</param> + <param index="6">Longitude/Y of goal</param> + <param index="7">Altitude/Z of goal</param> + </entry> + <entry value="95" name="MAV_CMD_NAV_LAST"> + <description>NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration</description> + <param index="1">Empty</param> + <param index="2">Empty</param> + <param index="3">Empty</param> + <param index="4">Empty</param> + <param index="5">Empty</param> + <param index="6">Empty</param> + <param index="7">Empty</param> + </entry> + <entry value="112" name="MAV_CMD_CONDITION_DELAY"> + <description>Delay mission state machine.</description> + <param index="1">Delay in seconds (decimal)</param> + <param index="2">Empty</param> + <param index="3">Empty</param> + <param index="4">Empty</param> + <param index="5">Empty</param> + <param index="6">Empty</param> + <param index="7">Empty</param> + </entry> + <entry value="113" name="MAV_CMD_CONDITION_CHANGE_ALT"> + <description>Ascend/descend at rate. Delay mission state machine until desired altitude reached.</description> + <param index="1">Descent / Ascend rate (m/s)</param> + <param index="2">Empty</param> + <param index="3">Empty</param> + <param index="4">Empty</param> + <param index="5">Empty</param> + <param index="6">Empty</param> + <param index="7">Finish Altitude</param> + </entry> + <entry value="114" name="MAV_CMD_CONDITION_DISTANCE"> + <description>Delay mission state machine until within desired distance of next NAV point.</description> + <param index="1">Distance (meters)</param> + <param index="2">Empty</param> + <param index="3">Empty</param> + <param index="4">Empty</param> + <param index="5">Empty</param> + <param index="6">Empty</param> + <param index="7">Empty</param> + </entry> + <entry value="115" name="MAV_CMD_CONDITION_YAW"> + <description>Reach a certain target angle.</description> + <param index="1">target angle: [0-360], 0 is north</param> + <param index="2">speed during yaw change:[deg per second]</param> + <param index="3">direction: negative: counter clockwise, positive: clockwise [-1,1]</param> + <param index="4">relative offset or absolute angle: [ 1,0]</param> + <param index="5">Empty</param> + <param index="6">Empty</param> + <param index="7">Empty</param> + </entry> + <entry value="159" name="MAV_CMD_CONDITION_LAST"> + <description>NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration</description> + <param index="1">Empty</param> + <param index="2">Empty</param> + <param index="3">Empty</param> + <param index="4">Empty</param> + <param index="5">Empty</param> + <param index="6">Empty</param> + <param index="7">Empty</param> + </entry> + <entry value="176" name="MAV_CMD_DO_SET_MODE"> + <description>Set system mode.</description> + <param index="1">Mode, as defined by ENUM MAV_MODE</param> + <param index="2">Empty</param> + <param index="3">Empty</param> + <param index="4">Empty</param> + <param index="5">Empty</param> + <param index="6">Empty</param> + <param index="7">Empty</param> + </entry> + <entry value="177" name="MAV_CMD_DO_JUMP"> + <description>Jump to the desired command in the mission list. Repeat this action only the specified number of times</description> + <param index="1">Sequence number</param> + <param index="2">Repeat count</param> + <param index="3">Empty</param> + <param index="4">Empty</param> + <param index="5">Empty</param> + <param index="6">Empty</param> + <param index="7">Empty</param> + </entry> + <entry value="178" name="MAV_CMD_DO_CHANGE_SPEED"> + <description>Change speed and/or throttle set points.</description> + <param index="1">Speed type (0=Airspeed, 1=Ground Speed)</param> + <param index="2">Speed (m/s, -1 indicates no change)</param> + <param index="3">Throttle ( Percent, -1 indicates no change)</param> + <param index="4">Empty</param> + <param index="5">Empty</param> + <param index="6">Empty</param> + <param index="7">Empty</param> + </entry> + <entry value="179" name="MAV_CMD_DO_SET_HOME"> + <description>Changes the home location either to the current location or a specified location.</description> + <param index="1">Use current (1=use current location, 0=use specified location)</param> + <param index="2">Empty</param> + <param index="3">Empty</param> + <param index="4">Empty</param> + <param index="5">Latitude</param> + <param index="6">Longitude</param> + <param index="7">Altitude</param> + </entry> + <entry value="180" name="MAV_CMD_DO_SET_PARAMETER"> + <description>Set a system parameter. Caution! Use of this command requires knowledge of the numeric enumeration value of the parameter.</description> + <param index="1">Parameter number</param> + <param index="2">Parameter value</param> + <param index="3">Empty</param> + <param index="4">Empty</param> + <param index="5">Empty</param> + <param index="6">Empty</param> + <param index="7">Empty</param> + </entry> + <entry value="181" name="MAV_CMD_DO_SET_RELAY"> + <description>Set a relay to a condition.</description> + <param index="1">Relay number</param> + <param index="2">Setting (1=on, 0=off, others possible depending on system hardware)</param> + <param index="3">Empty</param> + <param index="4">Empty</param> + <param index="5">Empty</param> + <param index="6">Empty</param> + <param index="7">Empty</param> + </entry> + <entry value="182" name="MAV_CMD_DO_REPEAT_RELAY"> + <description>Cycle a relay on and off for a desired number of cyles with a desired period.</description> + <param index="1">Relay number</param> + <param index="2">Cycle count</param> + <param index="3">Cycle time (seconds, decimal)</param> + <param index="4">Empty</param> + <param index="5">Empty</param> + <param index="6">Empty</param> + <param index="7">Empty</param> + </entry> + <entry value="183" name="MAV_CMD_DO_SET_SERVO"> + <description>Set a servo to a desired PWM value.</description> + <param index="1">Servo number</param> + <param index="2">PWM (microseconds, 1000 to 2000 typical)</param> + <param index="3">Empty</param> + <param index="4">Empty</param> + <param index="5">Empty</param> + <param index="6">Empty</param> + <param index="7">Empty</param> + </entry> + <entry value="184" name="MAV_CMD_DO_REPEAT_SERVO"> + <description>Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period.</description> + <param index="1">Servo number</param> + <param index="2">PWM (microseconds, 1000 to 2000 typical)</param> + <param index="3">Cycle count</param> + <param index="4">Cycle time (seconds)</param> + <param index="5">Empty</param> + <param index="6">Empty</param> + <param index="7">Empty</param> + </entry> + <entry value="200" name="MAV_CMD_DO_CONTROL_VIDEO"> + <description>Control onboard camera system.</description> + <param index="1">Camera ID (-1 for all)</param> + <param index="2">Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw</param> + <param index="3">Transmission mode: 0: video stream, >0: single images every n seconds (decimal)</param> + <param index="4">Recording: 0: disabled, 1: enabled compressed, 2: enabled raw</param> + <param index="5">Empty</param> + <param index="6">Empty</param> + <param index="7">Empty</param> + </entry> + <entry value="240" name="MAV_CMD_DO_LAST"> + <description>NOP - This command is only used to mark the upper limit of the DO commands in the enumeration</description> + <param index="1">Empty</param> + <param index="2">Empty</param> + <param index="3">Empty</param> + <param index="4">Empty</param> + <param index="5">Empty</param> + <param index="6">Empty</param> + <param index="7">Empty</param> + </entry> + <entry value="241" name="MAV_CMD_PREFLIGHT_CALIBRATION"> + <description>Trigger calibration. This command will be only accepted if in pre-flight mode.</description> + <param index="1">Gyro calibration: 0: no, 1: yes</param> + <param index="2">Magnetometer calibration: 0: no, 1: yes</param> + <param index="3">Ground pressure: 0: no, 1: yes</param> + <param index="4">Radio calibration: 0: no, 1: yes</param> + <param index="5">Empty</param> + <param index="6">Empty</param> + <param index="7">Empty</param> + </entry> + <entry value="242" name="MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS"> + <description>Set sensor offsets. This command will be only accepted if in pre-flight mode.</description> + <param index="1">Sensor to adjust the offsets for: 0: gyros, 1: accelerometer, 2: magnetometer, 3: barometer, 4: optical flow</param> + <param index="2">X axis offset (or generic dimension 1), in the sensor's raw units</param> + <param index="3">Y axis offset (or generic dimension 2), in the sensor's raw units</param> + <param index="4">Z axis offset (or generic dimension 3), in the sensor's raw units</param> + <param index="5">Generic dimension 4, in the sensor's raw units</param> + <param index="6">Generic dimension 5, in the sensor's raw units</param> + <param index="7">Generic dimension 6, in the sensor's raw units</param> + </entry> + <entry value="245" name="MAV_CMD_PREFLIGHT_STORAGE"> + <description>Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode.</description> + <param index="1">Parameter storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM</param> + <param index="2">Mission storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM</param> + <param index="3">Reserved</param> + <param index="4">Reserved</param> + <param index="5">Empty</param> + <param index="6">Empty</param> + <param index="7">Empty</param> + </entry> + <entry value="246" name="MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN"> + <description>Request the reboot or shutdown of system components.</description> + <param index="1">0: Do nothing for autopilot, 1: Reboot autopilot, 2: Shutdown autopilot.</param> + <param index="2">0: Do nothing for onboard computer, 1: Reboot onboard computer, 2: Shutdown onboard computer.</param> + <param index="3">Reserved</param> + <param index="4">Reserved</param> + <param index="5">Empty</param> + <param index="6">Empty</param> + <param index="7">Empty</param> + </entry> + <entry value="252" name="MAV_CMD_OVERRIDE_GOTO"> + <description>Hold / continue the current action</description> + <param index="1">MAV_GOTO_DO_HOLD: hold MAV_GOTO_DO_CONTINUE: continue with next item in mission plan</param> + <param index="2">MAV_GOTO_HOLD_AT_CURRENT_POSITION: Hold at current position MAV_GOTO_HOLD_AT_SPECIFIED_POSITION: hold at specified position</param> + <param index="3">MAV_FRAME coordinate frame of hold point</param> + <param index="4">Desired yaw angle in degrees</param> + <param index="5">Latitude / X position</param> + <param index="6">Longitude / Y position</param> + <param index="7">Altitude / Z position</param> + </entry> + <entry value="300" name="MAV_CMD_MISSION_START"> + <description>start running a mission</description> + <param index="1">first_item: the first mission item to run</param> + <param index="2">last_item: the last mission item to run (after this item is run, the mission ends)</param> + </entry> + <entry value="400" name="MAV_CMD_COMPONENT_ARM_DISARM"> + <description>Arms / Disarms a component</description> + <param index="1">1 to arm, 0 to disarm</param> + </entry> + </enum> + <enum name="MAV_DATA_STREAM"> + <description>Data stream IDs. A data stream is not a fixed set of messages, but rather a + recommendation to the autopilot software. Individual autopilots may or may not obey + the recommended messages.</description> + <entry value="0" name="MAV_DATA_STREAM_ALL"> + <description>Enable all data streams</description> + </entry> + <entry value="1" name="MAV_DATA_STREAM_RAW_SENSORS"> + <description>Enable IMU_RAW, GPS_RAW, GPS_STATUS packets.</description> + </entry> + <entry value="2" name="MAV_DATA_STREAM_EXTENDED_STATUS"> + <description>Enable GPS_STATUS, CONTROL_STATUS, AUX_STATUS</description> + </entry> + <entry value="3" name="MAV_DATA_STREAM_RC_CHANNELS"> + <description>Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW</description> + </entry> + <entry value="4" name="MAV_DATA_STREAM_RAW_CONTROLLER"> + <description>Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, NAV_CONTROLLER_OUTPUT.</description> + </entry> + <entry value="6" name="MAV_DATA_STREAM_POSITION"> + <description>Enable LOCAL_POSITION, GLOBAL_POSITION/GLOBAL_POSITION_INT messages.</description> + </entry> + <entry value="10" name="MAV_DATA_STREAM_EXTRA1"> + <description>Dependent on the autopilot</description> + </entry> + <entry value="11" name="MAV_DATA_STREAM_EXTRA2"> + <description>Dependent on the autopilot</description> + </entry> + <entry value="12" name="MAV_DATA_STREAM_EXTRA3"> + <description>Dependent on the autopilot</description> + </entry> + </enum> + <enum name="MAV_ROI"> + <description> The ROI (region of interest) for the vehicle. This can be + be used by the vehicle for camera/vehicle attitude alignment (see + MAV_CMD_NAV_ROI).</description> + <entry value="0" name="MAV_ROI_NONE"> + <description>No region of interest.</description> + </entry> + <entry value="1" name="MAV_ROI_WPNEXT"> + <description>Point toward next MISSION.</description> + </entry> + <entry value="2" name="MAV_ROI_WPINDEX"> + <description>Point toward given MISSION.</description> + </entry> + <entry value="3" name="MAV_ROI_LOCATION"> + <description>Point toward fixed location.</description> + </entry> + <entry value="4" name="MAV_ROI_TARGET"> + <description>Point toward of given id.</description> + </entry> + </enum> + <enum name="MAV_CMD_ACK"> + <description>ACK / NACK / ERROR values as a result of MAV_CMDs and for mission item transmission.</description> + <entry name="MAV_CMD_ACK_OK"> + <description>Command / mission item is ok.</description> + </entry> + <entry name="MAV_CMD_ACK_ERR_FAIL"> + <description>Generic error message if none of the other reasons fails or if no detailed error reporting is implemented.</description> + </entry> + <entry name="MAV_CMD_ACK_ERR_ACCESS_DENIED"> + <description>The system is refusing to accept this command from this source / communication partner.</description> + </entry> + <entry name="MAV_CMD_ACK_ERR_NOT_SUPPORTED"> + <description>Command or mission item is not supported, other commands would be accepted.</description> + </entry> + <entry name="MAV_CMD_ACK_ERR_COORDINATE_FRAME_NOT_SUPPORTED"> + <description>The coordinate frame of this command / mission item is not supported.</description> + </entry> + <entry name="MAV_CMD_ACK_ERR_COORDINATES_OUT_OF_RANGE"> + <description>The coordinate frame of this command is ok, but he coordinate values exceed the safety limits of this system. This is a generic error, please use the more specific error messages below if possible.</description> + </entry> + <entry name="MAV_CMD_ACK_ERR_X_LAT_OUT_OF_RANGE"> + <description>The X or latitude value is out of range.</description> + </entry> + <entry name="MAV_CMD_ACK_ERR_Y_LON_OUT_OF_RANGE"> + <description>The Y or longitude value is out of range.</description> + </entry> + <entry name="MAV_CMD_ACK_ERR_Z_ALT_OUT_OF_RANGE"> + <description>The Z or altitude value is out of range.</description> + </entry> + </enum> + <enum name="MAV_VAR"> + <description>type of a mavlink parameter</description> + <entry value="0" name="MAV_VAR_FLOAT"> + <description>32 bit float</description> + </entry> + <entry value="1" name="MAV_VAR_UINT8"> + <description>8 bit unsigned integer</description> + </entry> + <entry value="2" name="MAV_VAR_INT8"> + <description>8 bit signed integer</description> + </entry> + <entry value="3" name="MAV_VAR_UINT16"> + <description>16 bit unsigned integer</description> + </entry> + <entry value="4" name="MAV_VAR_INT16"> + <description>16 bit signed integer</description> + </entry> + <entry value="5" name="MAV_VAR_UINT32"> + <description>32 bit unsigned integer</description> + </entry> + <entry value="6" name="MAV_VAR_INT32"> + <description>32 bit signed integer</description> + </entry> + </enum> + <enum name="MAV_RESULT"> + <description>result from a mavlink command</description> + <entry value="0" name="MAV_RESULT_ACCEPTED"> + <description>Command ACCEPTED and EXECUTED</description> + </entry> + <entry value="1" name="MAV_RESULT_TEMPORARILY_REJECTED"> + <description>Command TEMPORARY REJECTED/DENIED</description> + </entry> + <entry value="2" name="MAV_RESULT_DENIED"> + <description>Command PERMANENTLY DENIED</description> + </entry> + <entry value="3" name="MAV_RESULT_UNSUPPORTED"> + <description>Command UNKNOWN/UNSUPPORTED</description> + </entry> + <entry value="4" name="MAV_RESULT_FAILED"> + <description>Command executed, but failed</description> + </entry> + </enum> + <enum name="MAV_MISSION_RESULT"> + <description>result in a mavlink mission ack</description> + <entry value="0" name="MAV_MISSION_ACCEPTED"> + <description>mission accepted OK</description> + </entry> + <entry value="1" name="MAV_MISSION_ERROR"> + <description>generic error / not accepting mission commands at all right now</description> + </entry> + <entry value="2" name="MAV_MISSION_UNSUPPORTED_FRAME"> + <description>coordinate frame is not supported</description> + </entry> + <entry value="3" name="MAV_MISSION_UNSUPPORTED"> + <description>command is not supported</description> + </entry> + <entry value="4" name="MAV_MISSION_NO_SPACE"> + <description>mission item exceeds storage space</description> + </entry> + <entry value="5" name="MAV_MISSION_INVALID"> + <description>one of the parameters has an invalid value</description> + </entry> + <entry value="6" name="MAV_MISSION_INVALID_PARAM1"> + <description>param1 has an invalid value</description> + </entry> + <entry value="7" name="MAV_MISSION_INVALID_PARAM2"> + <description>param2 has an invalid value</description> + </entry> + <entry value="8" name="MAV_MISSION_INVALID_PARAM3"> + <description>param3 has an invalid value</description> + </entry> + <entry value="9" name="MAV_MISSION_INVALID_PARAM4"> + <description>param4 has an invalid value</description> + </entry> + <entry value="10" name="MAV_MISSION_INVALID_PARAM5_X"> + <description>x/param5 has an invalid value</description> + </entry> + <entry value="11" name="MAV_MISSION_INVALID_PARAM6_Y"> + <description>y/param6 has an invalid value</description> + </entry> + <entry value="12" name="MAV_MISSION_INVALID_PARAM7"> + <description>param7 has an invalid value</description> + </entry> + <entry value="13" name="MAV_MISSION_INVALID_SEQUENCE"> + <description>received waypoint out of sequence</description> + </entry> + <entry value="14" name="MAV_MISSION_DENIED"> + <description>not accepting any mission commands from this communication partner</description> + </entry> + </enum> + <enum name="MAV_SEVERITY"> + <description>Indicates the severity level, generally used for status messages to indicate their relative urgency. Based on RFC-5424 using expanded definitions at: http://www.kiwisyslog.com/kb/info:-syslog-message-levels/.</description> + <entry value="0" name="MAV_SEVERITY_EMERGENCY"> + <description>System is unusable. This is a "panic" condition.</description> + </entry> + <entry value="1" name="MAV_SEVERITY_ALERT"> + <description>Action should be taken immediately. Indicates error in non-critical systems.</description> + </entry> + <entry value="2" name="MAV_SEVERITY_CRITICAL"> + <description>Action must be taken immediately. Indicates failure in a primary system.</description> + </entry> + <entry value="3" name="MAV_SEVERITY_ERROR"> + <description>Indicates an error in secondary/redundant systems.</description> + </entry> + <entry value="4" name="MAV_SEVERITY_WARNING"> + <description>Indicates about a possible future error if this is not resolved within a given timeframe. Example would be a low battery warning.</description> + </entry> + <entry value="5" name="MAV_SEVERITY_NOTICE"> + <description>An unusual event has occured, though not an error condition. This should be investigated for the root cause.</description> + </entry> + <entry value="6" name="MAV_SEVERITY_INFO"> + <description>Normal operational messages. Useful for logging. No action is required for these messages.</description> + </entry> + <entry value="7" name="MAV_SEVERITY_DEBUG"> + <description>Useful non-operational messages that can assist in debugging. These should not occur during normal operation.</description> + </entry> + </enum> + </enums> + <messages> + <message id="0" name="HEARTBEAT"> + <description>The heartbeat message shows that a system is present and responding. The type of the MAV and Autopilot hardware allow the receiving system to treat further messages from this system appropriate (e.g. by laying out the user interface based on the autopilot).</description> + <field type="uint8_t" name="type">Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)</field> + <field type="uint8_t" name="autopilot">Autopilot type / class. defined in MAV_AUTOPILOT ENUM</field> + <field type="uint8_t" name="base_mode">System mode bitfield, see MAV_MODE_FLAGS ENUM in mavlink/include/mavlink_types.h</field> + <field type="uint32_t" name="custom_mode">A bitfield for use for autopilot-specific flags.</field> + <field type="uint8_t" name="system_status">System status flag, see MAV_STATE ENUM</field> + <field type="uint8_t_mavlink_version" name="mavlink_version">MAVLink version, not writable by user, gets added by protocol because of magic data type: uint8_t_mavlink_version</field> + </message> + <message id="1" name="SYS_STATUS"> + <description>The general system state. If the system is following the MAVLink standard, the system state is mainly defined by three orthogonal states/modes: The system mode, which is either LOCKED (motors shut down and locked), MANUAL (system under RC control), GUIDED (system with autonomous position control, position setpoint controlled manually) or AUTO (system guided by path/waypoint planner). The NAV_MODE defined the current flight state: LIFTOFF (often an open-loop maneuver), LANDING, WAYPOINTS or VECTOR. This represents the internal navigation state machine. The system status shows wether the system is currently active or not and if an emergency occured. During the CRITICAL and EMERGENCY states the MAV is still considered to be active, but should start emergency procedures autonomously. After a failure occured it should first move from active to critical to allow manual intervention and then move to emergency after a certain timeout.</description> + <field type="uint32_t" name="onboard_control_sensors_present" print_format="0x%04x">Bitmask showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control</field> + <field type="uint32_t" name="onboard_control_sensors_enabled" print_format="0x%04x">Bitmask showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control</field> + <field type="uint32_t" name="onboard_control_sensors_health" print_format="0x%04x">Bitmask showing which onboard controllers and sensors are operational or have an error: Value of 0: not enabled. Value of 1: enabled. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control</field> + <field type="uint16_t" name="load">Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000</field> + <field type="uint16_t" name="voltage_battery">Battery voltage, in millivolts (1 = 1 millivolt)</field> + <field type="int16_t" name="current_battery">Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current</field> + <field type="int8_t" name="battery_remaining">Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery</field> + <field type="uint16_t" name="drop_rate_comm">Communication drops in percent, (0%: 0, 100%: 10'000), (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)</field> + <field type="uint16_t" name="errors_comm">Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)</field> + <field type="uint16_t" name="errors_count1">Autopilot-specific errors</field> + <field type="uint16_t" name="errors_count2">Autopilot-specific errors</field> + <field type="uint16_t" name="errors_count3">Autopilot-specific errors</field> + <field type="uint16_t" name="errors_count4">Autopilot-specific errors</field> + </message> + <message id="2" name="SYSTEM_TIME"> + <description>The system time is the time of the master clock, typically the computer clock of the main onboard computer.</description> + <field type="uint64_t" name="time_unix_usec">Timestamp of the master clock in microseconds since UNIX epoch.</field> + <field type="uint32_t" name="time_boot_ms">Timestamp of the component clock since boot time in milliseconds.</field> + </message> + <!-- FIXME to be removed / merged with SYSTEM_TIME --> + <message id="4" name="PING"> + <description>A ping message either requesting or responding to a ping. This allows to measure the system latencies, including serial port, radio modem and UDP connections.</description> + <field type="uint64_t" name="time_usec">Unix timestamp in microseconds</field> + <field type="uint32_t" name="seq">PING sequence</field> + <field type="uint8_t" name="target_system">0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system</field> + <field type="uint8_t" name="target_component">0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system</field> + </message> + <message id="5" name="CHANGE_OPERATOR_CONTROL"> + <description>Request to control this MAV</description> + <field type="uint8_t" name="target_system">System the GCS requests control for</field> + <field type="uint8_t" name="control_request">0: request control of this MAV, 1: Release control of this MAV</field> + <field type="uint8_t" name="version">0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch.</field> + <field type="char[25]" name="passkey">Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-"</field> + </message> + <message id="6" name="CHANGE_OPERATOR_CONTROL_ACK"> + <description>Accept / deny control of this MAV</description> + <field type="uint8_t" name="gcs_system_id">ID of the GCS this message </field> + <field type="uint8_t" name="control_request">0: request control of this MAV, 1: Release control of this MAV</field> + <field type="uint8_t" name="ack">0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control</field> + </message> + <message id="7" name="AUTH_KEY"> + <description>Emit an encrypted signature / key identifying this system. PLEASE NOTE: This protocol has been kept simple, so transmitting the key requires an encrypted channel for true safety.</description> + <field type="char[32]" name="key">key</field> + </message> + <message id="11" name="SET_MODE"> + <description>Set the system mode, as defined by enum MAV_MODE. There is no target component id as the mode is by definition for the overall aircraft, not only for one component.</description> + <field type="uint8_t" name="target_system">The system setting the mode</field> + <field type="uint8_t" name="base_mode">The new base mode</field> + <field type="uint32_t" name="custom_mode">The new autopilot-specific mode. This field can be ignored by an autopilot.</field> + </message> + <message id="20" name="PARAM_REQUEST_READ"> + <description>Request to read the onboard parameter with the param_id string id. Onboard parameters are stored as key[const char*] -> value[float]. This allows to send a parameter to any other component (such as the GCS) without the need of previous knowledge of possible parameter names. Thus the same GCS can store different parameters for different autopilots. See also http://qgroundcontrol.org/parameter_interface for a full documentation of QGroundControl and IMU code.</description> + <field type="uint8_t" name="target_system">System ID</field> + <field type="uint8_t" name="target_component">Component ID</field> + <field type="char[16]" name="param_id">Onboard parameter id</field> + <field type="int16_t" name="param_index">Parameter index. Send -1 to use the param ID field as identifier</field> + </message> + <message id="21" name="PARAM_REQUEST_LIST"> + <description>Request all parameters of this component. After his request, all parameters are emitted.</description> + <field type="uint8_t" name="target_system">System ID</field> + <field type="uint8_t" name="target_component">Component ID</field> + </message> + <message id="22" name="PARAM_VALUE"> + <description>Emit the value of a onboard parameter. The inclusion of param_count and param_index in the message allows the recipient to keep track of received parameters and allows him to re-request missing parameters after a loss or timeout.</description> + <field type="char[16]" name="param_id">Onboard parameter id</field> + <field type="float" name="param_value">Onboard parameter value</field> + <field type="uint8_t" name="param_type">Onboard parameter type: see MAV_VAR enum</field> + <field type="uint16_t" name="param_count">Total number of onboard parameters</field> + <field type="uint16_t" name="param_index">Index of this onboard parameter</field> + </message> + <message id="23" name="PARAM_SET"> + <description>Set a parameter value TEMPORARILY to RAM. It will be reset to default on system reboot. Send the ACTION MAV_ACTION_STORAGE_WRITE to PERMANENTLY write the RAM contents to EEPROM. IMPORTANT: The receiving component should acknowledge the new parameter value by sending a param_value message to all communication partners. This will also ensure that multiple GCS all have an up-to-date list of all parameters. If the sending GCS did not receive a PARAM_VALUE message within its timeout time, it should re-send the PARAM_SET message.</description> + <field type="uint8_t" name="target_system">System ID</field> + <field type="uint8_t" name="target_component">Component ID</field> + <field type="char[16]" name="param_id">Onboard parameter id</field> + <field type="float" name="param_value">Onboard parameter value</field> + <field type="uint8_t" name="param_type">Onboard parameter type: see MAV_VAR enum</field> + </message> + <message id="24" name="GPS_RAW_INT"> + <description>The global position, as returned by the Global Positioning System (GPS). This is + NOT the global position estimate of the sytem, but rather a RAW sensor value. See message GLOBAL_POSITION for the global position estimate. Coordinate frame is right-handed, Z-axis up (GPS frame).</description> + <field type="uint64_t" name="time_usec">Timestamp (microseconds since UNIX epoch or microseconds since system boot)</field> + <field type="uint8_t" name="fix_type">0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.</field> + <field type="int32_t" name="lat">Latitude in 1E7 degrees</field> + <field type="int32_t" name="lon">Longitude in 1E7 degrees</field> + <field type="int32_t" name="alt">Altitude in 1E3 meters (millimeters) above MSL</field> + <field type="uint16_t" name="eph">GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535</field> + <field type="uint16_t" name="epv">GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535</field> + <field type="uint16_t" name="vel">GPS ground speed (m/s * 100). If unknown, set to: 65535</field> + <field type="uint16_t" name="cog">Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535</field> + <field type="uint8_t" name="satellites_visible">Number of satellites visible. If unknown, set to 255</field> + </message> + <message id="25" name="GPS_STATUS"> + <description>The positioning status, as reported by GPS. This message is intended to display status information about each satellite visible to the receiver. See message GLOBAL_POSITION for the global position estimate. This message can contain information for up to 20 satellites.</description> + <field type="uint8_t" name="satellites_visible">Number of satellites visible</field> + <field type="uint8_t[20]" name="satellite_prn">Global satellite ID</field> + <field type="uint8_t[20]" name="satellite_used">0: Satellite not used, 1: used for localization</field> + <field type="uint8_t[20]" name="satellite_elevation">Elevation (0: right on top of receiver, 90: on the horizon) of satellite</field> + <field type="uint8_t[20]" name="satellite_azimuth">Direction of satellite, 0: 0 deg, 255: 360 deg.</field> + <field type="uint8_t[20]" name="satellite_snr">Signal to noise ratio of satellite</field> + </message> + <message id="26" name="SCALED_IMU"> + <description>The RAW IMU readings for the usual 9DOF sensor setup. This message should contain the scaled values to the described units</description> + <field type="uint32_t" name="time_boot_ms">Timestamp (milliseconds since system boot)</field> + <field type="int16_t" name="xacc">X acceleration (mg)</field> + <field type="int16_t" name="yacc">Y acceleration (mg)</field> + <field type="int16_t" name="zacc">Z acceleration (mg)</field> + <field type="int16_t" name="xgyro">Angular speed around X axis (millirad /sec)</field> + <field type="int16_t" name="ygyro">Angular speed around Y axis (millirad /sec)</field> + <field type="int16_t" name="zgyro">Angular speed around Z axis (millirad /sec)</field> + <field type="int16_t" name="xmag">X Magnetic field (milli tesla)</field> + <field type="int16_t" name="ymag">Y Magnetic field (milli tesla)</field> + <field type="int16_t" name="zmag">Z Magnetic field (milli tesla)</field> + </message> + <message id="27" name="RAW_IMU"> + <description>The RAW IMU readings for the usual 9DOF sensor setup. This message should always contain the true raw values without any scaling to allow data capture and system debugging.</description> + <field type="uint64_t" name="time_usec">Timestamp (microseconds since UNIX epoch or microseconds since system boot)</field> + <field type="int16_t" name="xacc">X acceleration (raw)</field> + <field type="int16_t" name="yacc">Y acceleration (raw)</field> + <field type="int16_t" name="zacc">Z acceleration (raw)</field> + <field type="int16_t" name="xgyro">Angular speed around X axis (raw)</field> + <field type="int16_t" name="ygyro">Angular speed around Y axis (raw)</field> + <field type="int16_t" name="zgyro">Angular speed around Z axis (raw)</field> + <field type="int16_t" name="xmag">X Magnetic field (raw)</field> + <field type="int16_t" name="ymag">Y Magnetic field (raw)</field> + <field type="int16_t" name="zmag">Z Magnetic field (raw)</field> + </message> + <message id="28" name="RAW_PRESSURE"> + <description>The RAW pressure readings for the typical setup of one absolute pressure and one differential pressure sensor. The sensor values should be the raw, UNSCALED ADC values.</description> + <field type="uint64_t" name="time_usec">Timestamp (microseconds since UNIX epoch or microseconds since system boot)</field> + <field type="int16_t" name="press_abs">Absolute pressure (raw)</field> + <field type="int16_t" name="press_diff1">Differential pressure 1 (raw)</field> + <field type="int16_t" name="press_diff2">Differential pressure 2 (raw)</field> + <field type="int16_t" name="temperature">Raw Temperature measurement (raw)</field> + </message> + <message id="29" name="SCALED_PRESSURE"> + <description>The pressure readings for the typical setup of one absolute and differential pressure sensor. The units are as specified in each field.</description> + <field type="uint32_t" name="time_boot_ms">Timestamp (microseconds since UNIX epoch or microseconds since system boot)</field> + <field type="float" name="press_abs">Absolute pressure (hectopascal)</field> + <field type="float" name="press_diff">Differential pressure 1 (hectopascal)</field> + <field type="int16_t" name="temperature">Temperature measurement (0.01 degrees celsius)</field> + </message> + <message id="30" name="ATTITUDE"> + <description>The attitude in the aeronautical frame (right-handed, Z-down, X-front, Y-right).</description> + <field type="uint32_t" name="time_boot_ms">Timestamp (milliseconds since system boot)</field> + <field type="float" name="roll">Roll angle (rad)</field> + <field type="float" name="pitch">Pitch angle (rad)</field> + <field type="float" name="yaw">Yaw angle (rad)</field> + <field type="float" name="rollspeed">Roll angular speed (rad/s)</field> + <field type="float" name="pitchspeed">Pitch angular speed (rad/s)</field> + <field type="float" name="yawspeed">Yaw angular speed (rad/s)</field> + </message> + <message id="31" name="ATTITUDE_QUATERNION"> + <description>The attitude in the aeronautical frame (right-handed, Z-down, X-front, Y-right), expressed as quaternion.</description> + <field type="uint32_t" name="time_boot_ms">Timestamp (milliseconds since system boot)</field> + <field type="float" name="q1">Quaternion component 1</field> + <field type="float" name="q2">Quaternion component 2</field> + <field type="float" name="q3">Quaternion component 3</field> + <field type="float" name="q4">Quaternion component 4</field> + <field type="float" name="rollspeed">Roll angular speed (rad/s)</field> + <field type="float" name="pitchspeed">Pitch angular speed (rad/s)</field> + <field type="float" name="yawspeed">Yaw angular speed (rad/s)</field> + </message> + <message id="32" name="LOCAL_POSITION_NED"> + <description>The filtered local position (e.g. fused computer vision and accelerometers). Coordinate frame is right-handed, Z-axis down (aeronautical frame, NED / north-east-down convention)</description> + <field type="uint32_t" name="time_boot_ms">Timestamp (milliseconds since system boot)</field> + <field type="float" name="x">X Position</field> + <field type="float" name="y">Y Position</field> + <field type="float" name="z">Z Position</field> + <field type="float" name="vx">X Speed</field> + <field type="float" name="vy">Y Speed</field> + <field type="float" name="vz">Z Speed</field> + </message> + <message id="33" name="GLOBAL_POSITION_INT"> + <description>The filtered global position (e.g. fused GPS and accelerometers). The position is in GPS-frame (right-handed, Z-up). It + is designed as scaled integer message since the resolution of float is not sufficient.</description> + <field type="uint32_t" name="time_boot_ms">Timestamp (milliseconds since system boot)</field> + <field type="int32_t" name="lat">Latitude, expressed as * 1E7</field> + <field type="int32_t" name="lon">Longitude, expressed as * 1E7</field> + <field type="int32_t" name="alt">Altitude in meters, expressed as * 1000 (millimeters), above MSL</field> + <field type="int32_t" name="relative_alt">Altitude above ground in meters, expressed as * 1000 (millimeters)</field> + <field type="int16_t" name="vx">Ground X Speed (Latitude), expressed as m/s * 100</field> + <field type="int16_t" name="vy">Ground Y Speed (Longitude), expressed as m/s * 100</field> + <field type="int16_t" name="vz">Ground Z Speed (Altitude), expressed as m/s * 100</field> + <field type="uint16_t" name="hdg">Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535</field> + </message> + <message id="34" name="RC_CHANNELS_SCALED"> + <description>The scaled values of the RC channels received. (-100%) -10000, (0%) 0, (100%) 10000</description> + <field type="uint32_t" name="time_boot_ms">Timestamp (milliseconds since system boot)</field> + <field type="uint8_t" name="port">Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos.</field> + <field type="int16_t" name="chan1_scaled">RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000</field> + <field type="int16_t" name="chan2_scaled">RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000</field> + <field type="int16_t" name="chan3_scaled">RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000</field> + <field type="int16_t" name="chan4_scaled">RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000</field> + <field type="int16_t" name="chan5_scaled">RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000</field> + <field type="int16_t" name="chan6_scaled">RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000</field> + <field type="int16_t" name="chan7_scaled">RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000</field> + <field type="int16_t" name="chan8_scaled">RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000</field> + <field type="uint8_t" name="rssi">Receive signal strength indicator, 0: 0%, 255: 100%</field> + </message> + <message id="35" name="RC_CHANNELS_RAW"> + <description>The RAW values of the RC channels received. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. Individual receivers/transmitters might violate this specification.</description> + <field type="uint32_t" name="time_boot_ms">Timestamp (milliseconds since system boot)</field> + <field type="uint8_t" name="port">Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos.</field> + <field type="uint16_t" name="chan1_raw">RC channel 1 value, in microseconds</field> + <field type="uint16_t" name="chan2_raw">RC channel 2 value, in microseconds</field> + <field type="uint16_t" name="chan3_raw">RC channel 3 value, in microseconds</field> + <field type="uint16_t" name="chan4_raw">RC channel 4 value, in microseconds</field> + <field type="uint16_t" name="chan5_raw">RC channel 5 value, in microseconds</field> + <field type="uint16_t" name="chan6_raw">RC channel 6 value, in microseconds</field> + <field type="uint16_t" name="chan7_raw">RC channel 7 value, in microseconds</field> + <field type="uint16_t" name="chan8_raw">RC channel 8 value, in microseconds</field> + <field type="uint8_t" name="rssi">Receive signal strength indicator, 0: 0%, 255: 100%</field> + </message> + <message id="36" name="SERVO_OUTPUT_RAW"> + <description>The RAW values of the servo outputs (for RC input from the remote, use the RC_CHANNELS messages). The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%.</description> + <field type="uint32_t" name="time_usec">Timestamp (since UNIX epoch or microseconds since system boot)</field> + <field type="uint8_t" name="port">Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos.</field> + <field type="uint16_t" name="servo1_raw">Servo output 1 value, in microseconds</field> + <field type="uint16_t" name="servo2_raw">Servo output 2 value, in microseconds</field> + <field type="uint16_t" name="servo3_raw">Servo output 3 value, in microseconds</field> + <field type="uint16_t" name="servo4_raw">Servo output 4 value, in microseconds</field> + <field type="uint16_t" name="servo5_raw">Servo output 5 value, in microseconds</field> + <field type="uint16_t" name="servo6_raw">Servo output 6 value, in microseconds</field> + <field type="uint16_t" name="servo7_raw">Servo output 7 value, in microseconds</field> + <field type="uint16_t" name="servo8_raw">Servo output 8 value, in microseconds</field> + </message> + <message id="37" name="MISSION_REQUEST_PARTIAL_LIST"> + <description>Request the overall list of MISSIONs from the system/component. http://qgroundcontrol.org/mavlink/waypoint_protocol</description> + <field type="uint8_t" name="target_system">System ID</field> + <field type="uint8_t" name="target_component">Component ID</field> + <field type="int16_t" name="start_index">Start index, 0 by default</field> + <field type="int16_t" name="end_index">End index, -1 by default (-1: send list to end). Else a valid index of the list</field> + </message> + <message id="38" name="MISSION_WRITE_PARTIAL_LIST"> + <description>This message is sent to the MAV to write a partial list. If start index == end index, only one item will be transmitted / updated. If the start index is NOT 0 and above the current list size, this request should be REJECTED!</description> + <field type="uint8_t" name="target_system">System ID</field> + <field type="uint8_t" name="target_component">Component ID</field> + <field type="int16_t" name="start_index">Start index, 0 by default and smaller / equal to the largest index of the current onboard list.</field> + <field type="int16_t" name="end_index">End index, equal or greater than start index.</field> + </message> + <message id="39" name="MISSION_ITEM"> + <description>Message encoding a mission item. This message is emitted to announce + the presence of a mission item and to set a mission item on the system. The mission item can be either in x, y, z meters (type: LOCAL) or x:lat, y:lon, z:altitude. Local frame is Z-down, right handed (NED), global frame is Z-up, right handed (ENU). See also http://qgroundcontrol.org/mavlink/waypoint_protocol.</description> + <field type="uint8_t" name="target_system">System ID</field> + <field type="uint8_t" name="target_component">Component ID</field> + <field type="uint16_t" name="seq">Sequence</field> + <field type="uint8_t" name="frame">The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h</field> + <field type="uint16_t" name="command">The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs</field> + <field type="uint8_t" name="current">false:0, true:1</field> + <field type="uint8_t" name="autocontinue">autocontinue to next wp</field> + <field type="float" name="param1">PARAM1 / For NAV command MISSIONs: Radius in which the MISSION is accepted as reached, in meters</field> + <field type="float" name="param2">PARAM2 / For NAV command MISSIONs: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds</field> + <field type="float" name="param3">PARAM3 / For LOITER command MISSIONs: Orbit to circle around the MISSION, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise.</field> + <field type="float" name="param4">PARAM4 / For NAV and LOITER command MISSIONs: Yaw orientation in degrees, [0..360] 0 = NORTH</field> + <field type="float" name="x">PARAM5 / local: x position, global: latitude</field> + <field type="float" name="y">PARAM6 / y position: global: longitude</field> + <field type="float" name="z">PARAM7 / z position: global: altitude</field> + </message> + <message id="40" name="MISSION_REQUEST"> + <description>Request the information of the mission item with the sequence number seq. The response of the system to this message should be a MISSION_ITEM message. http://qgroundcontrol.org/mavlink/waypoint_protocol</description> + <field type="uint8_t" name="target_system">System ID</field> + <field type="uint8_t" name="target_component">Component ID</field> + <field type="uint16_t" name="seq">Sequence</field> + </message> + <message id="41" name="MISSION_SET_CURRENT"> + <description>Set the mission item with sequence number seq as current item. This means that the MAV will continue to this mission item on the shortest path (not following the mission items in-between).</description> + <field type="uint8_t" name="target_system">System ID</field> + <field type="uint8_t" name="target_component">Component ID</field> + <field type="uint16_t" name="seq">Sequence</field> + </message> + <message id="42" name="MISSION_CURRENT"> + <description>Message that announces the sequence number of the current active mission item. The MAV will fly towards this mission item.</description> + <field type="uint16_t" name="seq">Sequence</field> + </message> + <message id="43" name="MISSION_REQUEST_LIST"> + <description>Request the overall list of mission items from the system/component.</description> + <field type="uint8_t" name="target_system">System ID</field> + <field type="uint8_t" name="target_component">Component ID</field> + </message> + <message id="44" name="MISSION_COUNT"> + <description>This message is emitted as response to MISSION_REQUEST_LIST by the MAV and to initiate a write transaction. The GCS can then request the individual mission item based on the knowledge of the total number of MISSIONs.</description> + <field type="uint8_t" name="target_system">System ID</field> + <field type="uint8_t" name="target_component">Component ID</field> + <field type="uint16_t" name="count">Number of mission items in the sequence</field> + </message> + <message id="45" name="MISSION_CLEAR_ALL"> + <description>Delete all mission items at once.</description> + <field type="uint8_t" name="target_system">System ID</field> + <field type="uint8_t" name="target_component">Component ID</field> + </message> + <message id="46" name="MISSION_ITEM_REACHED"> + <description>A certain mission item has been reached. The system will either hold this position (or circle on the orbit) or (if the autocontinue on the WP was set) continue to the next MISSION.</description> + <field type="uint16_t" name="seq">Sequence</field> + </message> + <message id="47" name="MISSION_ACK"> + <description>Ack message during MISSION handling. The type field states if this message is a positive ack (type=0) or if an error happened (type=non-zero).</description> + <field type="uint8_t" name="target_system">System ID</field> + <field type="uint8_t" name="target_component">Component ID</field> + <field type="uint8_t" name="type">See MAV_MISSION_RESULT enum</field> + </message> + <message id="48" name="SET_GPS_GLOBAL_ORIGIN"> + <description>As local MISSIONs exist, the global MISSION reference allows to transform between the local coordinate frame and the global (GPS) coordinate frame. This can be necessary when e.g. in- and outdoor settings are connected and the MAV should move from in- to outdoor.</description> + <field type="uint8_t" name="target_system">System ID</field> + <field type="int32_t" name="latitude">global position * 1E7</field> + <field type="int32_t" name="longitude">global position * 1E7</field> + <field type="int32_t" name="altitude">global position * 1000</field> + </message> + <message id="49" name="GPS_GLOBAL_ORIGIN"> + <description>Once the MAV sets a new GPS-Local correspondence, this message announces the origin (0,0,0) position</description> + <field type="int32_t" name="latitude">Latitude (WGS84), expressed as * 1E7</field> + <field type="int32_t" name="longitude">Longitude (WGS84), expressed as * 1E7</field> + <field type="int32_t" name="altitude">Altitude(WGS84), expressed as * 1000</field> + </message> + <message id="50" name="SET_LOCAL_POSITION_SETPOINT"> + <description>Set the setpoint for a local position controller. This is the position in local coordinates the MAV should fly to. This message is sent by the path/MISSION planner to the onboard position controller. As some MAVs have a degree of freedom in yaw (e.g. all helicopters/quadrotors), the desired yaw angle is part of the message.</description> + <field type="uint8_t" name="target_system">System ID</field> + <field type="uint8_t" name="target_component">Component ID</field> + <field type="uint8_t" name="coordinate_frame">Coordinate frame - valid values are only MAV_FRAME_LOCAL_NED or MAV_FRAME_LOCAL_ENU</field> + <field type="float" name="x">x position</field> + <field type="float" name="y">y position</field> + <field type="float" name="z">z position</field> + <field type="float" name="yaw">Desired yaw angle</field> + </message> + <message id="51" name="LOCAL_POSITION_SETPOINT"> + <description>Transmit the current local setpoint of the controller to other MAVs (collision avoidance) and to the GCS.</description> + <field type="uint8_t" name="coordinate_frame">Coordinate frame - valid values are only MAV_FRAME_LOCAL_NED or MAV_FRAME_LOCAL_ENU</field> + <field type="float" name="x">x position</field> + <field type="float" name="y">y position</field> + <field type="float" name="z">z position</field> + <field type="float" name="yaw">Desired yaw angle</field> + </message> + <message id="52" name="GLOBAL_POSITION_SETPOINT_INT"> + <description>Transmit the current local setpoint of the controller to other MAVs (collision avoidance) and to the GCS.</description> + <field type="uint8_t" name="coordinate_frame">Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT</field> + <field type="int32_t" name="latitude">WGS84 Latitude position in degrees * 1E7</field> + <field type="int32_t" name="longitude">WGS84 Longitude position in degrees * 1E7</field> + <field type="int32_t" name="altitude">WGS84 Altitude in meters * 1000 (positive for up)</field> + <field type="int16_t" name="yaw">Desired yaw angle in degrees * 100</field> + </message> + <message id="53" name="SET_GLOBAL_POSITION_SETPOINT_INT"> + <description>Set the current global position setpoint.</description> + <field type="uint8_t" name="coordinate_frame">Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT</field> + <field type="int32_t" name="latitude">WGS84 Latitude position in degrees * 1E7</field> + <field type="int32_t" name="longitude">WGS84 Longitude position in degrees * 1E7</field> + <field type="int32_t" name="altitude">WGS84 Altitude in meters * 1000 (positive for up)</field> + <field type="int16_t" name="yaw">Desired yaw angle in degrees * 100</field> + </message> + <message id="54" name="SAFETY_SET_ALLOWED_AREA"> + <description>Set a safety zone (volume), which is defined by two corners of a cube. This message can be used to tell the MAV which setpoints/MISSIONs to accept and which to reject. Safety areas are often enforced by national or competition regulations.</description> + <field type="uint8_t" name="target_system">System ID</field> + <field type="uint8_t" name="target_component">Component ID</field> + <field type="uint8_t" name="frame">Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down.</field> + <field type="float" name="p1x">x position 1 / Latitude 1</field> + <field type="float" name="p1y">y position 1 / Longitude 1</field> + <field type="float" name="p1z">z position 1 / Altitude 1</field> + <field type="float" name="p2x">x position 2 / Latitude 2</field> + <field type="float" name="p2y">y position 2 / Longitude 2</field> + <field type="float" name="p2z">z position 2 / Altitude 2</field> + </message> + <message id="55" name="SAFETY_ALLOWED_AREA"> + <description>Read out the safety zone the MAV currently assumes.</description> + <field type="uint8_t" name="frame">Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down.</field> + <field type="float" name="p1x">x position 1 / Latitude 1</field> + <field type="float" name="p1y">y position 1 / Longitude 1</field> + <field type="float" name="p1z">z position 1 / Altitude 1</field> + <field type="float" name="p2x">x position 2 / Latitude 2</field> + <field type="float" name="p2y">y position 2 / Longitude 2</field> + <field type="float" name="p2z">z position 2 / Altitude 2</field> + </message> + <message id="56" name="SET_ROLL_PITCH_YAW_THRUST"> + <description>Set roll, pitch and yaw.</description> + <field type="uint8_t" name="target_system">System ID</field> + <field type="uint8_t" name="target_component">Component ID</field> + <field type="float" name="roll">Desired roll angle in radians</field> + <field type="float" name="pitch">Desired pitch angle in radians</field> + <field type="float" name="yaw">Desired yaw angle in radians</field> + <field type="float" name="thrust">Collective thrust, normalized to 0 .. 1</field> + </message> + <message id="57" name="SET_ROLL_PITCH_YAW_SPEED_THRUST"> + <description>Set roll, pitch and yaw.</description> + <field type="uint8_t" name="target_system">System ID</field> + <field type="uint8_t" name="target_component">Component ID</field> + <field type="float" name="roll_speed">Desired roll angular speed in rad/s</field> + <field type="float" name="pitch_speed">Desired pitch angular speed in rad/s</field> + <field type="float" name="yaw_speed">Desired yaw angular speed in rad/s</field> + <field type="float" name="thrust">Collective thrust, normalized to 0 .. 1</field> + </message> + <message id="58" name="ROLL_PITCH_YAW_THRUST_SETPOINT"> + <description>Setpoint in roll, pitch, yaw currently active on the system.</description> + <field type="uint32_t" name="time_boot_ms">Timestamp in milliseconds since system boot</field> + <field type="float" name="roll">Desired roll angle in radians</field> + <field type="float" name="pitch">Desired pitch angle in radians</field> + <field type="float" name="yaw">Desired yaw angle in radians</field> + <field type="float" name="thrust">Collective thrust, normalized to 0 .. 1</field> + </message> + <message id="59" name="ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT"> + <description>Setpoint in rollspeed, pitchspeed, yawspeed currently active on the system.</description> + <field type="uint32_t" name="time_boot_ms">Timestamp in milliseconds since system boot</field> + <field type="float" name="roll_speed">Desired roll angular speed in rad/s</field> + <field type="float" name="pitch_speed">Desired pitch angular speed in rad/s</field> + <field type="float" name="yaw_speed">Desired yaw angular speed in rad/s</field> + <field type="float" name="thrust">Collective thrust, normalized to 0 .. 1</field> + </message> + <message id="60" name="SET_QUAD_MOTORS_SETPOINT"> + <description>Setpoint in the four motor speeds</description> + <field type="uint8_t" name="target_system">System ID of the system that should set these motor commands</field> + <field type="uint16_t" name="motor_front_nw">Front motor in + configuration, front left motor in x configuration</field> + <field type="uint16_t" name="motor_right_ne">Right motor in + configuration, front right motor in x configuration</field> + <field type="uint16_t" name="motor_back_se">Back motor in + configuration, back right motor in x configuration</field> + <field type="uint16_t" name="motor_left_sw">Left motor in + configuration, back left motor in x configuration</field> + </message> + <message id="61" name="SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST"> + <description></description> + <field type="uint8_t[6]" name="target_systems">System IDs for 6 quadrotors: 0..5, the ID's are the MAVLink IDs</field> + <field type="int16_t[6]" name="roll">Desired roll angle in radians, scaled to int16 for 6 quadrotors: 0..5</field> + <field type="int16_t[6]" name="pitch">Desired pitch angle in radians, scaled to int16 for 6 quadrotors: 0..5</field> + <field type="int16_t[6]" name="yaw">Desired yaw angle in radians, scaled to int16 for 6 quadrotors: 0..5</field> + <field type="uint16_t[6]" name="thrust">Collective thrust, scaled to uint16 for 6 quadrotors: 0..5</field> + </message> + <message id="62" name="NAV_CONTROLLER_OUTPUT"> + <description>Outputs of the APM navigation controller. The primary use of this message is to check the response and signs of the controller before actual flight and to assist with tuning controller parameters.</description> + <field type="float" name="nav_roll">Current desired roll in degrees</field> + <field type="float" name="nav_pitch">Current desired pitch in degrees</field> + <field type="int16_t" name="nav_bearing">Current desired heading in degrees</field> + <field type="int16_t" name="target_bearing">Bearing to current MISSION/target in degrees</field> + <field type="uint16_t" name="wp_dist">Distance to active MISSION in meters</field> + <field type="float" name="alt_error">Current altitude error in meters</field> + <field type="float" name="aspd_error">Current airspeed error in meters/second</field> + <field type="float" name="xtrack_error">Current crosstrack error on x-y plane in meters</field> + </message> + <message id="64" name="STATE_CORRECTION"> + <description>Corrects the systems state by adding an error correction term to the position and velocity, and by rotating the attitude by a correction angle.</description> + <field type="float" name="xErr">x position error</field> + <field type="float" name="yErr">y position error</field> + <field type="float" name="zErr">z position error</field> + <field type="float" name="rollErr">roll error (radians)</field> + <field type="float" name="pitchErr">pitch error (radians)</field> + <field type="float" name="yawErr">yaw error (radians)</field> + <field type="float" name="vxErr">x velocity</field> + <field type="float" name="vyErr">y velocity</field> + <field type="float" name="vzErr">z velocity</field> + </message> + <message id="66" name="REQUEST_DATA_STREAM"> + <field type="uint8_t" name="target_system">The target requested to send the message stream.</field> + <field type="uint8_t" name="target_component">The target requested to send the message stream.</field> + <field type="uint8_t" name="req_stream_id">The ID of the requested data stream</field> + <field type="uint16_t" name="req_message_rate">The requested interval between two messages of this type</field> + <field type="uint8_t" name="start_stop">1 to start sending, 0 to stop sending.</field> + </message> + <message id="67" name="DATA_STREAM"> + <field type="uint8_t" name="stream_id">The ID of the requested data stream</field> + <field type="uint16_t" name="message_rate">The requested interval between two messages of this type</field> + <field type="uint8_t" name="on_off">1 stream is enabled, 0 stream is stopped.</field> + </message> + <message id="69" name="MANUAL_CONTROL"> + <field type="uint8_t" name="target">The system to be controlled</field> + <field type="float" name="roll">roll</field> + <field type="float" name="pitch">pitch</field> + <field type="float" name="yaw">yaw</field> + <field type="float" name="thrust">thrust</field> + <field type="uint8_t" name="roll_manual">roll control enabled auto:0, manual:1</field> + <field type="uint8_t" name="pitch_manual">pitch auto:0, manual:1</field> + <field type="uint8_t" name="yaw_manual">yaw auto:0, manual:1</field> + <field type="uint8_t" name="thrust_manual">thrust auto:0, manual:1</field> + </message> + <message id="70" name="RC_CHANNELS_OVERRIDE"> + <description>The RAW values of the RC channels sent to the MAV to override info received from the RC radio. A value of -1 means no change to that channel. A value of 0 means control of that channel should be released back to the RC radio. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. Individual receivers/transmitters might violate this specification.</description> + <field type="uint8_t" name="target_system">System ID</field> + <field type="uint8_t" name="target_component">Component ID</field> + <field type="uint16_t" name="chan1_raw">RC channel 1 value, in microseconds</field> + <field type="uint16_t" name="chan2_raw">RC channel 2 value, in microseconds</field> + <field type="uint16_t" name="chan3_raw">RC channel 3 value, in microseconds</field> + <field type="uint16_t" name="chan4_raw">RC channel 4 value, in microseconds</field> + <field type="uint16_t" name="chan5_raw">RC channel 5 value, in microseconds</field> + <field type="uint16_t" name="chan6_raw">RC channel 6 value, in microseconds</field> + <field type="uint16_t" name="chan7_raw">RC channel 7 value, in microseconds</field> + <field type="uint16_t" name="chan8_raw">RC channel 8 value, in microseconds</field> + </message> + <message id="74" name="VFR_HUD"> + <description>Metrics typically displayed on a HUD for fixed wing aircraft</description> + <field type="float" name="airspeed">Current airspeed in m/s</field> + <field type="float" name="groundspeed">Current ground speed in m/s</field> + <field type="int16_t" name="heading">Current heading in degrees, in compass units (0..360, 0=north)</field> + <field type="uint16_t" name="throttle">Current throttle setting in integer percent, 0 to 100</field> + <field type="float" name="alt">Current altitude (MSL), in meters</field> + <field type="float" name="climb">Current climb rate in meters/second</field> + </message> + <message id="76" name="COMMAND_LONG"> + <description>Send a command with up to four parameters to the MAV</description> + <field type="uint8_t" name="target_system">System which should execute the command</field> + <field type="uint8_t" name="target_component">Component which should execute the command, 0 for all components</field> + <field type="uint16_t" name="command">Command ID, as defined by MAV_CMD enum.</field> + <field type="uint8_t" name="confirmation">0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command)</field> + <field type="float" name="param1">Parameter 1, as defined by MAV_CMD enum.</field> + <field type="float" name="param2">Parameter 2, as defined by MAV_CMD enum.</field> + <field type="float" name="param3">Parameter 3, as defined by MAV_CMD enum.</field> + <field type="float" name="param4">Parameter 4, as defined by MAV_CMD enum.</field> + <field type="float" name="param5">Parameter 5, as defined by MAV_CMD enum.</field> + <field type="float" name="param6">Parameter 6, as defined by MAV_CMD enum.</field> + <field type="float" name="param7">Parameter 7, as defined by MAV_CMD enum.</field> + </message> + <message id="77" name="COMMAND_ACK"> + <description>Report status of a command. Includes feedback wether the command was executed.</description> + <field type="uint16_t" name="command">Command ID, as defined by MAV_CMD enum.</field> + <field type="uint8_t" name="result">See MAV_RESULT enum</field> + </message> + <message id="89" name="LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET"> + <description>The offset in X, Y, Z and yaw between the LOCAL_POSITION_NED messages of MAV X and the global coordinate frame in NED coordinates. Coordinate frame is right-handed, Z-axis down (aeronautical frame, NED / north-east-down convention)</description> + <field type="uint32_t" name="time_boot_ms">Timestamp (milliseconds since system boot)</field> + <field type="float" name="x">X Position</field> + <field type="float" name="y">Y Position</field> + <field type="float" name="z">Z Position</field> + <field type="float" name="roll">Roll</field> + <field type="float" name="pitch">Pitch</field> + <field type="float" name="yaw">Yaw</field> + </message> + <message id="90" name="HIL_STATE"> + <description>Sent from simulation to autopilot. This packet is useful for high throughput applications such as hardware in the loop simulations.</description> + <field type="uint64_t" name="time_usec">Timestamp (microseconds since UNIX epoch or microseconds since system boot)</field> + <field type="float" name="roll">Roll angle (rad)</field> + <field type="float" name="pitch">Pitch angle (rad)</field> + <field type="float" name="yaw">Yaw angle (rad)</field> + <field type="float" name="rollspeed">Roll angular speed (rad/s)</field> + <field type="float" name="pitchspeed">Pitch angular speed (rad/s)</field> + <field type="float" name="yawspeed">Yaw angular speed (rad/s)</field> + <field type="int32_t" name="lat">Latitude, expressed as * 1E7</field> + <field type="int32_t" name="lon">Longitude, expressed as * 1E7</field> + <field type="int32_t" name="alt">Altitude in meters, expressed as * 1000 (millimeters)</field> + <field type="int16_t" name="vx">Ground X Speed (Latitude), expressed as m/s * 100</field> + <field type="int16_t" name="vy">Ground Y Speed (Longitude), expressed as m/s * 100</field> + <field type="int16_t" name="vz">Ground Z Speed (Altitude), expressed as m/s * 100</field> + <field type="int16_t" name="xacc">X acceleration (mg)</field> + <field type="int16_t" name="yacc">Y acceleration (mg)</field> + <field type="int16_t" name="zacc">Z acceleration (mg)</field> + </message> + <message id="91" name="HIL_CONTROLS"> + <description>Sent from autopilot to simulation. Hardware in the loop control outputs</description> + <field name="time_usec" type="uint64_t">Timestamp (microseconds since UNIX epoch or microseconds since system boot)</field> + <field name="roll_ailerons" type="float">Control output -1 .. 1</field> + <field name="pitch_elevator" type="float">Control output -1 .. 1</field> + <field name="yaw_rudder" type="float">Control output -1 .. 1</field> + <field name="throttle" type="float">Throttle 0 .. 1</field> + <field name="aux1" type="float">Aux 1, -1 .. 1</field> + <field name="aux2" type="float">Aux 2, -1 .. 1</field> + <field name="aux3" type="float">Aux 3, -1 .. 1</field> + <field name="aux4" type="float">Aux 4, -1 .. 1</field> + <field name="mode" type="uint8_t">System mode (MAV_MODE)</field> + <field name="nav_mode" type="uint8_t">Navigation mode (MAV_NAV_MODE)</field> + </message> + <message id="92" name="HIL_RC_INPUTS_RAW"> + <description>Sent from simulation to autopilot. The RAW values of the RC channels received. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. Individual receivers/transmitters might violate this specification.</description> + <field type="uint64_t" name="time_usec">Timestamp (microseconds since UNIX epoch or microseconds since system boot)</field> + <field type="uint16_t" name="chan1_raw">RC channel 1 value, in microseconds</field> + <field type="uint16_t" name="chan2_raw">RC channel 2 value, in microseconds</field> + <field type="uint16_t" name="chan3_raw">RC channel 3 value, in microseconds</field> + <field type="uint16_t" name="chan4_raw">RC channel 4 value, in microseconds</field> + <field type="uint16_t" name="chan5_raw">RC channel 5 value, in microseconds</field> + <field type="uint16_t" name="chan6_raw">RC channel 6 value, in microseconds</field> + <field type="uint16_t" name="chan7_raw">RC channel 7 value, in microseconds</field> + <field type="uint16_t" name="chan8_raw">RC channel 8 value, in microseconds</field> + <field type="uint16_t" name="chan9_raw">RC channel 9 value, in microseconds</field> + <field type="uint16_t" name="chan10_raw">RC channel 10 value, in microseconds</field> + <field type="uint16_t" name="chan11_raw">RC channel 11 value, in microseconds</field> + <field type="uint16_t" name="chan12_raw">RC channel 12 value, in microseconds</field> + <field type="uint8_t" name="rssi">Receive signal strength indicator, 0: 0%, 255: 100%</field> + </message> + <message id="100" name="OPTICAL_FLOW"> + <description>Optical flow from a flow sensor (e.g. optical mouse sensor)</description> + <field type="uint64_t" name="time_usec">Timestamp (UNIX)</field> + <field type="uint8_t" name="sensor_id">Sensor ID</field> + <field type="int16_t" name="flow_x">Flow in pixels in x-sensor direction</field> + <field type="int16_t" name="flow_y">Flow in pixels in y-sensor direction</field> + <field type="float" name="flow_comp_m_x">Flow in meters in x-sensor direction, angular-speed compensated</field> + <field type="float" name="flow_comp_m_y">Flow in meters in y-sensor direction, angular-speed compensated</field> + <field type="uint8_t" name="quality">Optical flow quality / confidence. 0: bad, 255: maximum quality</field> + <field type="float" name="ground_distance">Ground distance in meters. Positive value: distance known. Negative value: Unknown distance</field> + </message> + <message id="101" name="GLOBAL_VISION_POSITION_ESTIMATE"> + <field type="uint64_t" name="usec">Timestamp (milliseconds)</field> + <field type="float" name="x">Global X position</field> + <field type="float" name="y">Global Y position</field> + <field type="float" name="z">Global Z position</field> + <field type="float" name="roll">Roll angle in rad</field> + <field type="float" name="pitch">Pitch angle in rad</field> + <field type="float" name="yaw">Yaw angle in rad</field> + </message> + <message id="102" name="VISION_POSITION_ESTIMATE"> + <field type="uint64_t" name="usec">Timestamp (milliseconds)</field> + <field type="float" name="x">Global X position</field> + <field type="float" name="y">Global Y position</field> + <field type="float" name="z">Global Z position</field> + <field type="float" name="roll">Roll angle in rad</field> + <field type="float" name="pitch">Pitch angle in rad</field> + <field type="float" name="yaw">Yaw angle in rad</field> + </message> + <message id="103" name="VISION_SPEED_ESTIMATE"> + <field type="uint64_t" name="usec">Timestamp (milliseconds)</field> + <field type="float" name="x">Global X speed</field> + <field type="float" name="y">Global Y speed</field> + <field type="float" name="z">Global Z speed</field> + </message> + <message id="104" name="VICON_POSITION_ESTIMATE"> + <field type="uint64_t" name="usec">Timestamp (milliseconds)</field> + <field type="float" name="x">Global X position</field> + <field type="float" name="y">Global Y position</field> + <field type="float" name="z">Global Z position</field> + <field type="float" name="roll">Roll angle in rad</field> + <field type="float" name="pitch">Pitch angle in rad</field> + <field type="float" name="yaw">Yaw angle in rad</field> + </message> + <!-- MESSAGE IDs 150 - 240: Space for custom messages in individual projectname_messages.xml files --> + <message id="249" name="MEMORY_VECT"> + <description>Send raw controller memory. The use of this message is discouraged for normal packets, but a quite efficient way for testing new messages and getting experimental debug output.</description> + <field type="uint16_t" name="address">Starting address of the debug variables</field> + <field type="uint8_t" name="ver">Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below</field> + <field type="uint8_t" name="type">Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14</field> + <field type="int8_t[32]" name="value">Memory contents at specified address</field> + </message> + <message id="250" name="DEBUG_VECT"> + <field type="char[10]" name="name">Name</field> + <field type="uint64_t" name="time_usec">Timestamp</field> + <field type="float" name="x">x</field> + <field type="float" name="y">y</field> + <field type="float" name="z">z</field> + </message> + <message id="251" name="NAMED_VALUE_FLOAT"> + <description>Send a key-value pair as float. The use of this message is discouraged for normal packets, but a quite efficient way for testing new messages and getting experimental debug output.</description> + <field type="uint32_t" name="time_boot_ms">Timestamp (milliseconds since system boot)</field> + <field type="char[10]" name="name">Name of the debug variable</field> + <field type="float" name="value">Floating point value</field> + </message> + <message id="252" name="NAMED_VALUE_INT"> + <description>Send a key-value pair as integer. The use of this message is discouraged for normal packets, but a quite efficient way for testing new messages and getting experimental debug output.</description> + <field type="uint32_t" name="time_boot_ms">Timestamp (milliseconds since system boot)</field> + <field type="char[10]" name="name">Name of the debug variable</field> + <field type="int32_t" name="value">Signed integer value</field> + </message> + <message id="253" name="STATUSTEXT"> + <description>Status text message. These messages are printed in yellow in the COMM console of QGroundControl. WARNING: They consume quite some bandwidth, so use only for important status and error messages. If implemented wisely, these messages are buffered on the MCU and sent only at a limited rate (e.g. 10 Hz).</description> + <field type="uint8_t" name="severity">Severity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY.</field> + <field type="char[50]" name="text">Status text message, without null termination character</field> + </message> + <message id="254" name="DEBUG"> + <description>Send a debug value. The index is used to discriminate between values. These values show up in the plot of QGroundControl as DEBUG N.</description> + <field type="uint32_t" name="time_boot_ms">Timestamp (milliseconds since system boot)</field> + <field type="uint8_t" name="ind">index of debug variable</field> + <field type="float" name="value">DEBUG value</field> + </message> + </messages> +</mavlink> diff --git a/libraries/GCS_MAVLink/message_definitions_v1.0/matrixpilot.xml b/libraries/GCS_MAVLink/message_definitions_v1.0/matrixpilot.xml new file mode 100644 index 0000000000000000000000000000000000000000..9e86eaf999dec7f8207b93c1e874c23384b215db --- /dev/null +++ b/libraries/GCS_MAVLink/message_definitions_v1.0/matrixpilot.xml @@ -0,0 +1,14 @@ +<?xml version='1.0'?> +<mavlink> + <include>common.xml</include> + <!-- note that MatrixPilot specific messages should use the command id + range from 150 to 250, to leave plenty of room for growth + of common.xml + + If you prototype a message here, then you should consider if it + is general enough to move into common.xml later + --> + <messages> + + </messages> +</mavlink> diff --git a/libraries/GCS_MAVLink/message_definitions_v1.0/minimal.xml b/libraries/GCS_MAVLink/message_definitions_v1.0/minimal.xml new file mode 100644 index 0000000000000000000000000000000000000000..88985a5c98106e224b230038c4ed0d1a9079d23d --- /dev/null +++ b/libraries/GCS_MAVLink/message_definitions_v1.0/minimal.xml @@ -0,0 +1,189 @@ +<?xml version='1.0'?> +<mavlink> + <version>2</version> + <enums> + <enum name="MAV_AUTOPILOT"> + <description>Micro air vehicle / autopilot classes. This identifies the individual model.</description> + <entry value="0" name="MAV_AUTOPILOT_GENERIC"> + <description>Generic autopilot, full support for everything</description> + </entry> + <entry value="1" name="MAV_AUTOPILOT_PIXHAWK"> + <description>PIXHAWK autopilot, http://pixhawk.ethz.ch</description> + </entry> + <entry value="2" name="MAV_AUTOPILOT_SLUGS"> + <description>SLUGS autopilot, http://slugsuav.soe.ucsc.edu</description> + </entry> + <entry value="3" name="MAV_AUTOPILOT_ARDUPILOTMEGA"> + <description>ArduPilotMega / ArduCopter, http://diydrones.com</description> + </entry> + <entry value="4" name="MAV_AUTOPILOT_OPENPILOT"> + <description>OpenPilot, http://openpilot.org</description> + </entry> + <entry value="5" name="MAV_AUTOPILOT_GENERIC_WAYPOINTS_ONLY"> + <description>Generic autopilot only supporting simple waypoints</description> + </entry> + <entry value="6" name="MAV_AUTOPILOT_GENERIC_WAYPOINTS_AND_SIMPLE_NAVIGATION_ONLY"> + <description>Generic autopilot supporting waypoints and other simple navigation commands</description> + </entry> + <entry value="7" name="MAV_AUTOPILOT_GENERIC_MISSION_FULL"> + <description>Generic autopilot supporting the full mission command set</description> + </entry> + <entry value="8" name="MAV_AUTOPILOT_INVALID"> + <description>No valid autopilot, e.g. a GCS or other MAVLink component</description> + </entry> + <entry value="9" name="MAV_AUTOPILOT_PPZ"> + <description>PPZ UAV - http://nongnu.org/paparazzi</description> + </entry> + <entry value="10" name="MAV_AUTOPILOT_UDB"> + <description>UAV Dev Board</description> + </entry> + <entry value="11" name="MAV_AUTOPILOT_FP"> + <description>FlexiPilot</description> + </entry> + </enum> + <enum name="MAV_TYPE"> + <entry value="0" name="MAV_TYPE_GENERIC"> + <description>Generic micro air vehicle.</description> + </entry> + <entry value="1" name="MAV_TYPE_FIXED_WING"> + <description>Fixed wing aircraft.</description> + </entry> + <entry value="2" name="MAV_TYPE_QUADROTOR"> + <description>Quadrotor</description> + </entry> + <entry value="3" name="MAV_TYPE_COAXIAL"> + <description>Coaxial helicopter</description> + </entry> + <entry value="4" name="MAV_TYPE_HELICOPTER"> + <description>Normal helicopter with tail rotor.</description> + </entry> + <entry value="5" name="MAV_TYPE_ANTENNA_TRACKER"> + <description>Ground installation</description> + </entry> + <entry value="6" name="MAV_TYPE_GCS"> + <description>Operator control unit / ground control station</description> + </entry> + <entry value="7" name="MAV_TYPE_AIRSHIP"> + <description>Airship, controlled</description> + </entry> + <entry value="8" name="MAV_TYPE_FREE_BALLOON"> + <description>Free balloon, uncontrolled</description> + </entry> + <entry value="9" name="MAV_TYPE_ROCKET"> + <description>Rocket</description> + </entry> + <entry value="10" name="MAV_TYPE_GROUND_ROVER"> + <description>Ground rover</description> + </entry> + <entry value="11" name="MAV_TYPE_SURFACE_BOAT"> + <description>Surface vessel, boat, ship</description> + </entry> + <entry value="12" name="MAV_TYPE_SUBMARINE"> + <description>Submarine</description> + </entry> + <entry value="13" name="MAV_TYPE_HEXAROTOR"> + <description>Hexarotor</description> + </entry> + <entry value="14" name="MAV_TYPE_OCTOROTOR"> + <description>Octorotor</description> + </entry> + <entry value="15" name="MAV_TYPE_TRICOPTER"> + <description>Octorotor</description> + </entry> + <entry value="16" name="MAV_TYPE_FLAPPING_WING"> + <description>Flapping wing</description> + </entry> + </enum> + <enum name="MAV_MODE_FLAG"> + <description>These flags encode the MAV mode.</description> + <entry value="128" name="MAV_MODE_FLAG_SAFETY_ARMED"> + <description>0b10000000 MAV safety set to armed. Motors are enabled / running / can start. Ready to fly.</description> + </entry> + <entry value="64" name="MAV_MODE_FLAG_MANUAL_INPUT_ENABLED"> + <description>0b01000000 remote control input is enabled.</description> + </entry> + <entry value="32" name="MAV_MODE_FLAG_HIL_ENABLED"> + <description>0b00100000 hardware in the loop simulation. All motors / actuators are blocked, but internal software is full operational.</description> + </entry> + <entry value="16" name="MAV_MODE_FLAG_STABILIZE_ENABLED"> + <description>0b00010000 system stabilizes electronically its attitude (and optionally position). It needs however further control inputs to move around.</description> + </entry> + <entry value="8" name="MAV_MODE_FLAG_GUIDED_ENABLED"> + <description>0b00001000 guided mode enabled, system flies MISSIONs / mission items.</description> + </entry> + <entry value="4" name="MAV_MODE_FLAG_AUTO_ENABLED"> + <description>0b00000100 autonomous mode enabled, system finds its own goal positions. Guided flag can be set or not, depends on the actual implementation.</description> + </entry> + <entry value="2" name="MAV_MODE_FLAG_TEST_ENABLED"> + <description>0b00000010 system has a test mode enabled. This flag is intended for temporary system tests and should not be used for stable implementations.</description> + </entry> + <entry value="1" name="MAV_MODE_FLAG_CUSTOM_MODE_ENABLED"> + <description>0b00000001 Reserved for future use.</description> + </entry> + </enum> + <enum name="MAV_MODE_FLAG_DECODE_POSITION"> + <description>These values encode the bit positions of the decode position. These values can be used to read the value of a flag bit by combining the base_mode variable with AND with the flag position value. The result will be either 0 or 1, depending on if the flag is set or not.</description> + <entry value="128" name="MAV_MODE_FLAG_DECODE_POSITION_SAFETY"> + <description>First bit: 10000000</description> + </entry> + <entry value="64" name="MAV_MODE_FLAG_DECODE_POSITION_MANUAL"> + <description>Second bit: 01000000</description> + </entry> + <entry value="32" name="MAV_MODE_FLAG_DECODE_POSITION_HIL"> + <description>Third bit: 00100000</description> + </entry> + <entry value="16" name="MAV_MODE_FLAG_DECODE_POSITION_STABILIZE"> + <description>Fourth bit: 00010000</description> + </entry> + <entry value="8" name="MAV_MODE_FLAG_DECODE_POSITION_GUIDED"> + <description>Fifth bit: 00001000</description> + </entry> + <entry value="4" name="MAV_MODE_FLAG_DECODE_POSITION_AUTO"> + <description>Sixt bit: 00000100</description> + </entry> + <entry value="2" name="MAV_MODE_FLAG_DECODE_POSITION_TEST"> + <description>Seventh bit: 00000010</description> + </entry> + <entry value="1" name="MAV_MODE_FLAG_DECODE_POSITION_CUSTOM_MODE"> + <description>Eighth bit: 00000001</description> + </entry> + </enum> + <enum name="MAV_STATE"> + <entry value="0" name="MAV_STATE_UNINIT"> + <description>Uninitialized system, state is unknown.</description> + </entry> + <entry name="MAV_STATE_BOOT"> + <description>System is booting up.</description> + </entry> + <entry name="MAV_STATE_CALIBRATING"> + <description>System is calibrating and not flight-ready.</description> + </entry> + <entry name="MAV_STATE_STANDBY"> + <description>System is grounded and on standby. It can be launched any time.</description> + </entry> + <entry name="MAV_STATE_ACTIVE"> + <description>System is active and might be already airborne. Motors are engaged.</description> + </entry> + <entry name="MAV_STATE_CRITICAL"> + <description>System is in a non-normal flight mode. It can however still navigate.</description> + </entry> + <entry name="MAV_STATE_EMERGENCY"> + <description>System is in a non-normal flight mode. It lost control over parts or over the whole airframe. It is in mayday and going down.</description> + </entry> + <entry name="MAV_STATE_POWEROFF"> + <description>System just initialized its power-down sequence, will shut down now.</description> + </entry> + </enum> + </enums> + <messages> + <message id="0" name="HEARTBEAT"> + <description>The heartbeat message shows that a system is present and responding. The type of the MAV and Autopilot hardware allow the receiving system to treat further messages from this system appropriate (e.g. by laying out the user interface based on the autopilot).</description> + <field type="uint8_t" name="type">Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)</field> + <field type="uint8_t" name="autopilot">Autopilot type / class. defined in MAV_AUTOPILOT ENUM</field> + <field type="uint8_t" name="base_mode">System mode bitfield, see MAV_MODE_FLAGS ENUM in mavlink/include/mavlink_types.h</field> + <field type="uint32_t" name="custom_mode">A bitfield for use for autopilot-specific flags.</field> + <field type="uint8_t" name="system_status">System status flag, see MAV_STATE ENUM</field> + <field type="uint8_t_mavlink_version" name="mavlink_version">MAVLink version</field> + </message> + </messages> +</mavlink> diff --git a/libraries/GCS_MAVLink/message_definitions_v1.0/pixhawk.xml b/libraries/GCS_MAVLink/message_definitions_v1.0/pixhawk.xml new file mode 100644 index 0000000000000000000000000000000000000000..8efe0f8ec1b8f98bc6b5e88de3701770a71a4c7f --- /dev/null +++ b/libraries/GCS_MAVLink/message_definitions_v1.0/pixhawk.xml @@ -0,0 +1,195 @@ +<?xml version='1.0'?> +<mavlink> + <include>common.xml</include> + <enums> + <enum name="DATA_TYPES"> + <description>Content Types for data transmission handshake</description> + <entry value="1" name="DATA_TYPE_JPEG_IMAGE"/> + <entry value="2" name="DATA_TYPE_RAW_IMAGE"/> + <entry value="3" name="DATA_TYPE_KINECT"/> + </enum> + </enums> + <messages> + <message id="151" name="SET_CAM_SHUTTER"> + <field type="uint8_t" name="cam_no">Camera id</field> + <field type="uint8_t" name="cam_mode">Camera mode: 0 = auto, 1 = manual</field> + <field type="uint8_t" name="trigger_pin">Trigger pin, 0-3 for PtGrey FireFly</field> + <field type="uint16_t" name="interval">Shutter interval, in microseconds</field> + <field type="uint16_t" name="exposure">Exposure time, in microseconds</field> + <field type="float" name="gain">Camera gain</field> + </message> + <message id="152" name="IMAGE_TRIGGERED"> + <field type="uint64_t" name="timestamp">Timestamp</field> + <field type="uint32_t" name="seq">IMU seq</field> + <field type="float" name="roll">Roll angle in rad</field> + <field type="float" name="pitch">Pitch angle in rad</field> + <field type="float" name="yaw">Yaw angle in rad</field> + <field type="float" name="local_z">Local frame Z coordinate (height over ground)</field> + <field type="float" name="lat">GPS X coordinate</field> + <field type="float" name="lon">GPS Y coordinate</field> + <field type="float" name="alt">Global frame altitude</field> + <field type="float" name="ground_x">Ground truth X</field> + <field type="float" name="ground_y">Ground truth Y</field> + <field type="float" name="ground_z">Ground truth Z</field> + </message> + <message id="153" name="IMAGE_TRIGGER_CONTROL"> + <field type="uint8_t" name="enable">0 to disable, 1 to enable</field> + </message> + <message id="154" name="IMAGE_AVAILABLE"> + <field type="uint64_t" name="cam_id">Camera id</field> + <field type="uint8_t" name="cam_no">Camera # (starts with 0)</field> + <field type="uint64_t" name="timestamp">Timestamp</field> + <field type="uint64_t" name="valid_until">Until which timestamp this buffer will stay valid</field> + <field type="uint32_t" name="img_seq">The image sequence number</field> + <field type="uint32_t" name="img_buf_index">Position of the image in the buffer, starts with 0</field> + <field type="uint16_t" name="width">Image width</field> + <field type="uint16_t" name="height">Image height</field> + <field type="uint16_t" name="depth">Image depth</field> + <field type="uint8_t" name="channels">Image channels</field> + <field type="uint32_t" name="key">Shared memory area key</field> + <field type="uint32_t" name="exposure">Exposure time, in microseconds</field> + <field type="float" name="gain">Camera gain</field> + <field type="float" name="roll">Roll angle in rad</field> + <field type="float" name="pitch">Pitch angle in rad</field> + <field type="float" name="yaw">Yaw angle in rad</field> + <field type="float" name="local_z">Local frame Z coordinate (height over ground)</field> + <field type="float" name="lat">GPS X coordinate</field> + <field type="float" name="lon">GPS Y coordinate</field> + <field type="float" name="alt">Global frame altitude</field> + <field type="float" name="ground_x">Ground truth X</field> + <field type="float" name="ground_y">Ground truth Y</field> + <field type="float" name="ground_z">Ground truth Z</field> + </message> + <message id="160" name="SET_POSITION_CONTROL_OFFSET"> + <description>Message sent to the MAV to set a new offset from the currently controlled position</description> + <field type="uint8_t" name="target_system">System ID</field> + <field type="uint8_t" name="target_component">Component ID</field> + <field type="float" name="x">x position offset</field> + <field type="float" name="y">y position offset</field> + <field type="float" name="z">z position offset</field> + <field type="float" name="yaw">yaw orientation offset in radians, 0 = NORTH</field> + </message> + <!-- Message sent by the MAV once it sets a new position as reference in the controller --> + <message id="170" name="POSITION_CONTROL_SETPOINT"> + <field type="uint16_t" name="id">ID of waypoint, 0 for plain position</field> + <field type="float" name="x">x position</field> + <field type="float" name="y">y position</field> + <field type="float" name="z">z position</field> + <field type="float" name="yaw">yaw orientation in radians, 0 = NORTH</field> + </message> + <message id="171" name="MARKER"> + <field type="uint16_t" name="id">ID</field> + <field type="float" name="x">x position</field> + <field type="float" name="y">y position</field> + <field type="float" name="z">z position</field> + <field type="float" name="roll">roll orientation</field> + <field type="float" name="pitch">pitch orientation</field> + <field type="float" name="yaw">yaw orientation</field> + </message> + <message id="172" name="RAW_AUX"> + <field type="uint16_t" name="adc1">ADC1 (J405 ADC3, LPC2148 AD0.6)</field> + <field type="uint16_t" name="adc2">ADC2 (J405 ADC5, LPC2148 AD0.2)</field> + <field type="uint16_t" name="adc3">ADC3 (J405 ADC6, LPC2148 AD0.1)</field> + <field type="uint16_t" name="adc4">ADC4 (J405 ADC7, LPC2148 AD1.3)</field> + <field type="uint16_t" name="vbat">Battery voltage</field> + <field type="int16_t" name="temp">Temperature (degrees celcius)</field> + <field type="int32_t" name="baro">Barometric pressure (hecto Pascal)</field> + </message> + <message id="180" name="WATCHDOG_HEARTBEAT"> + <field type="uint16_t" name="watchdog_id">Watchdog ID</field> + <field type="uint16_t" name="process_count">Number of processes</field> + </message> + <message id="181" name="WATCHDOG_PROCESS_INFO"> + <field type="uint16_t" name="watchdog_id">Watchdog ID</field> + <field type="uint16_t" name="process_id">Process ID</field> + <field type="char[100]" name="name">Process name</field> + <field type="char[147]" name="arguments">Process arguments</field> + <field type="int32_t" name="timeout">Timeout (seconds)</field> + </message> + <message id="182" name="WATCHDOG_PROCESS_STATUS"> + <field type="uint16_t" name="watchdog_id">Watchdog ID</field> + <field type="uint16_t" name="process_id">Process ID</field> + <field type="uint8_t" name="state">Is running / finished / suspended / crashed</field> + <field type="uint8_t" name="muted">Is muted</field> + <field type="int32_t" name="pid">PID</field> + <field type="uint16_t" name="crashes">Number of crashes</field> + </message> + <message id="183" name="WATCHDOG_COMMAND"> + <field type="uint8_t" name="target_system_id">Target system ID</field> + <field type="uint16_t" name="watchdog_id">Watchdog ID</field> + <field type="uint16_t" name="process_id">Process ID</field> + <field type="uint8_t" name="command_id">Command ID</field> + </message> + <message id="190" name="PATTERN_DETECTED"> + <field type="uint8_t" name="type">0: Pattern, 1: Letter</field> + <field type="float" name="confidence">Confidence of detection</field> + <field type="char[100]" name="file">Pattern file name</field> + <field type="uint8_t" name="detected">Accepted as true detection, 0 no, 1 yes</field> + </message> + <message id="191" name="POINT_OF_INTEREST"> + <description>Notifies the operator about a point of interest (POI). This can be anything detected by the + system. This generic message is intented to help interfacing to generic visualizations and to display + the POI on a map. + </description> + <field type="uint8_t" name="type">0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug</field> + <field type="uint8_t" name="color">0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta</field> + <field type="uint8_t" name="coordinate_system">0: global, 1:local</field> + <field type="uint16_t" name="timeout">0: no timeout, >1: timeout in seconds</field> + <field type="float" name="x">X Position</field> + <field type="float" name="y">Y Position</field> + <field type="float" name="z">Z Position</field> + <field type="char[26]" name="name">POI name</field> + </message> + <message id="192" name="POINT_OF_INTEREST_CONNECTION"> + <description>Notifies the operator about the connection of two point of interests (POI). This can be anything detected by the + system. This generic message is intented to help interfacing to generic visualizations and to display + the POI on a map. + </description> + <field type="uint8_t" name="type">0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug</field> + <field type="uint8_t" name="color">0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta</field> + <field type="uint8_t" name="coordinate_system">0: global, 1:local</field> + <field type="uint16_t" name="timeout">0: no timeout, >1: timeout in seconds</field> + <field type="float" name="xp1">X1 Position</field> + <field type="float" name="yp1">Y1 Position</field> + <field type="float" name="zp1">Z1 Position</field> + <field type="float" name="xp2">X2 Position</field> + <field type="float" name="yp2">Y2 Position</field> + <field type="float" name="zp2">Z2 Position</field> + <field type="char[26]" name="name">POI connection name</field> + </message> + <message id="193" name="DATA_TRANSMISSION_HANDSHAKE"> + <field type="uint8_t" name="type">type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h)</field> + <field type="uint32_t" name="size">total data size in bytes (set on ACK only)</field> + <field type="uint16_t" name="width">Width of a matrix or image</field> + <field type="uint16_t" name="height">Height of a matrix or image</field> + <field type="uint8_t" name="packets">number of packets beeing sent (set on ACK only)</field> + <field type="uint8_t" name="payload">payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only)</field> + <field type="uint8_t" name="jpg_quality">JPEG quality out of [1,100]</field> + </message> + <message id="194" name="ENCAPSULATED_DATA"> + <field type="uint16_t" name="seqnr">sequence number (starting with 0 on every transmission)</field> + <field type="uint8_t[253]" name="data">image data bytes</field> + </message> + <message id="195" name="BRIEF_FEATURE"> + <field type="float" name="x">x position in m</field> + <field type="float" name="y">y position in m</field> + <field type="float" name="z">z position in m</field> + <field type="uint8_t" name="orientation_assignment">Orientation assignment 0: false, 1:true</field> + <field type="uint16_t" name="size">Size in pixels</field> + <field type="uint16_t" name="orientation">Orientation</field> + <field type="uint8_t[32]" name="descriptor">Descriptor</field> + <field type="float" name="response">Harris operator response at this location</field> + </message> + <message id="200" name="ATTITUDE_CONTROL"> + <field type="uint8_t" name="target">The system to be controlled</field> + <field type="float" name="roll">roll</field> + <field type="float" name="pitch">pitch</field> + <field type="float" name="yaw">yaw</field> + <field type="float" name="thrust">thrust</field> + <field type="uint8_t" name="roll_manual">roll control enabled auto:0, manual:1</field> + <field type="uint8_t" name="pitch_manual">pitch auto:0, manual:1</field> + <field type="uint8_t" name="yaw_manual">yaw auto:0, manual:1</field> + <field type="uint8_t" name="thrust_manual">thrust auto:0, manual:1</field> + </message> + </messages> +</mavlink> diff --git a/libraries/GCS_MAVLink/message_definitions_v1.0/sensesoar.xml b/libraries/GCS_MAVLink/message_definitions_v1.0/sensesoar.xml new file mode 100644 index 0000000000000000000000000000000000000000..4c7140f93d690128b2e0feaf51f8ec9292875110 --- /dev/null +++ b/libraries/GCS_MAVLink/message_definitions_v1.0/sensesoar.xml @@ -0,0 +1,83 @@ +<?xml version='1.0'?> +<mavlink> + <include>common.xml</include> + <enums> + <enum name="SENSESOAR_MODE"> + <description> Different flight modes </description> + <entry name="SENSESOAR_MODE_GLIDING"> Gliding mode with motors off</entry> + <entry name="SENSESOAR_MODE_AUTONOMOUS"> Autonomous flight</entry> + <entry name="SENSESOAR_MODE_MANUAL"> RC controlled</entry> + </enum> + </enums> + <messages> + <message id="170" name="OBS_POSITION"> + Position estimate of the observer in global frame + <field type="int32_t" name="lon">Longitude expressed in 1E7</field> + <field type="int32_t" name="lat">Latitude expressed in 1E7</field> + <field type="int32_t" name="alt">Altitude expressed in milimeters</field> + </message> + <message id="172" name="OBS_VELOCITY"> + velocity estimate of the observer in NED inertial frame + <field type="float[3]" name="vel">Velocity</field> + </message> + <message id="174" name="OBS_ATTITUDE"> + attitude estimate of the observer + <field type="double[4]" name="quat">Quaternion re;im</field> + </message> + <message id="176" name="OBS_WIND"> + Wind estimate in NED inertial frame + <field type="float[3]" name="wind">Wind</field> + </message> + <message id="178" name="OBS_AIR_VELOCITY"> + Estimate of the air velocity + <field type="float" name="magnitude">Air speed</field> + <field type="float" name="aoa">angle of attack</field> + <field type="float" name="slip">slip angle</field> + </message> + <message id="180" name="OBS_BIAS"> + IMU biases + <field type="float[3]" name="accBias">accelerometer bias</field> + <field type="float[3]" name="gyroBias">gyroscope bias</field> + </message> + <message id="182" name="OBS_QFF"> + estimate of the pressure at sea level + <field type="float" name="qff">Wind</field> + </message> + <message id="183" name="OBS_AIR_TEMP"> + ambient air temperature + <field type="float" name="airT">Air Temperatur</field> + </message> + <message id="184" name="FILT_ROT_VEL"> + filtered rotational velocity + <field type="float[3]" name="rotVel">rotational velocity</field> + </message> + <message id="186" name="LLC_OUT"> + low level control output + <field type="int16_t[4]" name="servoOut">Servo signal</field> + <field type="int16_t[2]" name="MotorOut">motor signal</field> + </message> + <message id="188" name="PM_ELEC"> + Power managment + <field type="float" name="PwCons">current power consumption</field> + <field type="float" name="BatStat">battery status</field> + <field type="float[3]" name="PwGen">Power generation from each module</field> + </message> + <message id="190" name="SYS_Stat"> + system status + <field type="uint8_t" name="gps">gps status</field> + <field type="uint8_t" name="act">actuator status</field> + <field type="uint8_t" name="mod">module status</field> + <field type="uint8_t" name="commRssi">module status</field> + </message> + <message id="192" name="CMD_AIRSPEED_CHNG"> + change commanded air speed + <field type="uint8_t" name="target">Target ID</field> + <field type="float" name="spCmd">commanded airspeed</field> + </message> + <message id="194" name="CMD_AIRSPEED_ACK"> + accept change of airspeed + <field type="float" name="spCmd">commanded airspeed</field> + <field type="uint8_t" name="ack">0:ack, 1:nack</field> + </message> + </messages> +</mavlink> diff --git a/libraries/GCS_MAVLink/message_definitions_v1.0/slugs.xml b/libraries/GCS_MAVLink/message_definitions_v1.0/slugs.xml new file mode 100644 index 0000000000000000000000000000000000000000..5b7a9f7a5a7872f5fec3fa1f06680043054e553c --- /dev/null +++ b/libraries/GCS_MAVLink/message_definitions_v1.0/slugs.xml @@ -0,0 +1,144 @@ +<?xml version="1.0"?> +<mavlink> + <include>common.xml</include> + + <!-- <enums> + <enum name="SLUGS_ACTION" > + <description> Slugs Actions </description> + <entry name = "SLUGS_ACTION_NONE"> + <entry name = "SLUGS_ACTION_SUCCESS"> + <entry name = "SLUGS_ACTION_FAIL"> + <entry name = "SLUGS_ACTION_EEPROM"> + <entry name = "SLUGS_ACTION_MODE_CHANGE"> + <entry name = "SLUGS_ACTION_MODE_REPORT"> + <entry name = "SLUGS_ACTION_PT_CHANGE"> + <entry name = "SLUGS_ACTION_PT_REPORT"> + <entry name = "SLUGS_ACTION_PID_CHANGE"> + <entry name = "SLUGS_ACTION_PID_REPORT"> + <entry name = "SLUGS_ACTION_WP_CHANGE"> + <entry name = "SLUGS_ACTION_WP_REPORT"> + <entry name = "SLUGS_ACTION_MLC_CHANGE"> + <entry name = "SLUGS_ACTION_MLC_REPORT"> + </enum> + + <enum name="WP_PROTOCOL_STATE" > + <description> Waypoint Protocol States </description> + <entry name = "WP_PROT_IDLE"> + <entry name = "WP_PROT_LIST_REQUESTED"> + <entry name = "WP_PROT_NUM_SENT"> + <entry name = "WP_PROT_TX_WP"> + <entry name = "WP_PROT_RX_WP"> + <entry name = "WP_PROT_SENDING_WP_IDLE"> + <entry name = "WP_PROT_GETTING_WP_IDLE"> + </enum> + +</enums> --> + + <messages> + + <message name="CPU_LOAD" id="170"> + Sensor and DSC control loads. + <field name="sensLoad" type="uint8_t">Sensor DSC Load</field> + <field name="ctrlLoad" type="uint8_t">Control DSC Load</field> + <field name="batVolt" type="uint16_t">Battery Voltage in millivolts</field> + </message> + + <message name="AIR_DATA" id="171"> + Air data for altitude and airspeed computation. + <field name="dynamicPressure" type="float">Dynamic pressure (Pa)</field> + <field name="staticPressure" type="float">Static pressure (Pa)</field> + <field name="temperature" type="uint16_t">Board temperature</field> + </message> + + <message name="SENSOR_BIAS" id="172"> + Accelerometer and gyro biases. + <field name="axBias" type="float">Accelerometer X bias (m/s)</field> + <field name="ayBias" type="float">Accelerometer Y bias (m/s)</field> + <field name="azBias" type="float">Accelerometer Z bias (m/s)</field> + <field name="gxBias" type="float">Gyro X bias (rad/s)</field> + <field name="gyBias" type="float">Gyro Y bias (rad/s)</field> + <field name="gzBias" type="float">Gyro Z bias (rad/s)</field> + </message> + + <message name="DIAGNOSTIC" id="173"> + Configurable diagnostic messages. + <field name="diagFl1" type="float">Diagnostic float 1</field> + <field name="diagFl2" type="float">Diagnostic float 2</field> + <field name="diagFl3" type="float">Diagnostic float 3</field> + <field name="diagSh1" type="int16_t">Diagnostic short 1</field> + <field name="diagSh2" type="int16_t">Diagnostic short 2</field> + <field name="diagSh3" type="int16_t">Diagnostic short 3</field> + </message> + + <message name="SLUGS_NAVIGATION" id="176"> + Data used in the navigation algorithm. + <field name="u_m" type="float">Measured Airspeed prior to the Nav Filter</field> + <field name="phi_c" type="float">Commanded Roll</field> + <field name="theta_c" type="float">Commanded Pitch</field> + <field name="psiDot_c" type="float">Commanded Turn rate</field> + <field name="ay_body" type="float">Y component of the body acceleration</field> + <field name="totalDist" type="float">Total Distance to Run on this leg of Navigation</field> + <field name="dist2Go" type="float">Remaining distance to Run on this leg of Navigation</field> + <field name="fromWP" type="uint8_t">Origin WP</field> + <field name="toWP" type="uint8_t">Destination WP</field> + </message> + + <message name="DATA_LOG" id="177"> + Configurable data log probes to be used inside Simulink + <field name="fl_1" type="float">Log value 1 </field> + <field name="fl_2" type="float">Log value 2 </field> + <field name="fl_3" type="float">Log value 3 </field> + <field name="fl_4" type="float">Log value 4 </field> + <field name="fl_5" type="float">Log value 5 </field> + <field name="fl_6" type="float">Log value 6 </field> + </message> + + <message name="GPS_DATE_TIME" id="179"> + Pilot console PWM messges. + <field name="year" type="uint8_t">Year reported by Gps </field> + <field name="month" type="uint8_t">Month reported by Gps </field> + <field name="day" type="uint8_t">Day reported by Gps </field> + <field name="hour" type="uint8_t">Hour reported by Gps </field> + <field name="min" type="uint8_t">Min reported by Gps </field> + <field name="sec" type="uint8_t">Sec reported by Gps </field> + <field name="visSat" type="uint8_t">Visible sattelites reported by Gps </field> + </message> + + <message name="MID_LVL_CMDS" id="180"> + Mid Level commands sent from the GS to the autopilot. These are only sent when being opperated in mid-level commands mode from the ground; for periodic report of these commands generated from the autopilot see message XXXX. + <field name="target" type="uint8_t">The system setting the commands</field> + <field name="hCommand" type="float">Commanded Airspeed</field> + <field name="uCommand" type="float">Log value 2 </field> + <field name="rCommand" type="float">Log value 3 </field> + </message> + + + <message name="CTRL_SRFC_PT" id="181"> + This message configures the Selective Passthrough mode. it allows to select which control surfaces the Pilot can control from his console. It is implemented as a bitfield as follows: + Position Bit Code + ================================= + 15-8 Reserved + 7 dt_pass 128 + 6 dla_pass 64 + 5 dra_pass 32 + 4 dr_pass 16 + 3 dle_pass 8 + 2 dre_pass 4 + 1 dlf_pass 2 + 0 drf_pass 1 + Where Bit 15 is the MSb. 0 = AP has control of the surface; 1 = Pilot Console has control of the surface. + <field name="target" type="uint8_t">The system setting the commands</field> + <field name="bitfieldPt" type="uint16_t">Bitfield containing the PT configuration</field> + </message> + + + + <message name="SLUGS_ACTION" id="183"> + Action messages focused on the SLUGS AP. + <field name="target" type="uint8_t">The system reporting the action</field> + <field name="actionId" type="uint8_t">Action ID. See apDefinitions.h in the SLUGS /clib directory for the ID names</field> + <field name="actionVal" type="uint16_t">Value associated with the action</field> + </message> + + </messages> +</mavlink> diff --git a/libraries/GCS_MAVLink/message_definitions_v1.0/test.xml b/libraries/GCS_MAVLink/message_definitions_v1.0/test.xml new file mode 100644 index 0000000000000000000000000000000000000000..02bc03204d11a3565e9a39ce4b2646e935a6bd2b --- /dev/null +++ b/libraries/GCS_MAVLink/message_definitions_v1.0/test.xml @@ -0,0 +1,31 @@ +<?xml version='1.0'?> +<mavlink> + <version>3</version> + <messages> + <message id="0" name="TEST_TYPES"> + <description>Test all field types</description> + <field type="char" name="c">char</field> + <field type="char[10]" name="s">string</field> + <field type="uint8_t" name="u8">uint8_t</field> + <field type="uint16_t" name="u16">uint16_t</field> + <field print_format="0x%08x" type="uint32_t" name="u32">uint32_t</field> + <field type="uint64_t" name="u64">uint64_t</field> + <field type="int8_t" name="s8">int8_t</field> + <field type="int16_t" name="s16">int16_t</field> + <field type="int32_t" name="s32">int32_t</field> + <field type="int64_t" name="s64">int64_t</field> + <field type="float" name="f">float</field> + <field type="double" name="d">double</field> + <field type="uint8_t[3]" name="u8_array">uint8_t_array</field> + <field type="uint16_t[3]" name="u16_array">uint16_t_array</field> + <field type="uint32_t[3]" name="u32_array">uint32_t_array</field> + <field type="uint64_t[3]" name="u64_array">uint64_t_array</field> + <field type="int8_t[3]" name="s8_array">int8_t_array</field> + <field type="int16_t[3]" name="s16_array">int16_t_array</field> + <field type="int32_t[3]" name="s32_array">int32_t_array</field> + <field type="int64_t[3]" name="s64_array">int64_t_array</field> + <field type="float[3]" name="f_array">float_array</field> + <field type="double[3]" name="d_array">double_array</field> + </message> + </messages> +</mavlink> diff --git a/libraries/GCS_MAVLink/message_definitions_v1.0/ualberta.xml b/libraries/GCS_MAVLink/message_definitions_v1.0/ualberta.xml new file mode 100644 index 0000000000000000000000000000000000000000..5e53e141e9f018e943abfd25bc1f58c0a0091574 --- /dev/null +++ b/libraries/GCS_MAVLink/message_definitions_v1.0/ualberta.xml @@ -0,0 +1,54 @@ +<?xml version='1.0'?> +<mavlink> + <include>common.xml</include> + <enums> + <enum name="UALBERTA_AUTOPILOT_MODE"> + <description>Available autopilot modes for ualberta uav</description> + <entry name="MODE_MANUAL_DIRECT">Raw input pulse widts sent to output</entry> + <entry name="MODE_MANUAL_SCALED">Inputs are normalized using calibration, the converted back to raw pulse widths for output</entry> + <entry name="MODE_AUTO_PID_ATT"> dfsdfs</entry> + <entry name="MODE_AUTO_PID_VEL"> dfsfds</entry> + <entry name="MODE_AUTO_PID_POS"> dfsdfsdfs</entry> + </enum> + <enum name="UALBERTA_NAV_MODE"> + <description>Navigation filter mode</description> + <entry name="NAV_AHRS_INIT" /> + <entry name="NAV_AHRS">AHRS mode</entry> + <entry name="NAV_INS_GPS_INIT">INS/GPS initialization mode</entry> + <entry name="NAV_INS_GPS">INS/GPS mode</entry> + </enum> + <enum name="UALBERTA_PILOT_MODE"> + <description>Mode currently commanded by pilot</description> + <entry name="PILOT_MANUAL"> sdf</entry> + <entry name="PILOT_AUTO"> dfs</entry> + <entry name="PILOT_ROTO"> Rotomotion mode </entry> + </enum> + </enums> + <messages> + <message id="220" name="NAV_FILTER_BIAS"> + <description>Accelerometer and Gyro biases from the navigation filter</description> + <field type="uint64_t" name="usec">Timestamp (microseconds)</field> + <field type="float" name="accel_0">b_f[0]</field> + <field type="float" name="accel_1">b_f[1]</field> + <field type="float" name="accel_2">b_f[2]</field> + <field type="float" name="gyro_0">b_f[0]</field> + <field type="float" name="gyro_1">b_f[1]</field> + <field type="float" name="gyro_2">b_f[2]</field> + </message> + <message id="221" name="RADIO_CALIBRATION"> + <description>Complete set of calibration parameters for the radio</description> + <field type="uint16_t[3]" name="aileron">Aileron setpoints: left, center, right</field> + <field type="uint16_t[3]" name="elevator">Elevator setpoints: nose down, center, nose up</field> + <field type="uint16_t[3]" name="rudder">Rudder setpoints: nose left, center, nose right</field> + <field type="uint16_t[2]" name="gyro">Tail gyro mode/gain setpoints: heading hold, rate mode</field> + <field type="uint16_t[5]" name="pitch">Pitch curve setpoints (every 25%)</field> + <field type="uint16_t[5]" name="throttle">Throttle curve setpoints (every 25%)</field> + </message> + <message id="222" name="UALBERTA_SYS_STATUS"> + <description>System status specific to ualberta uav</description> + <field type="uint8_t" name="mode">System mode, see UALBERTA_AUTOPILOT_MODE ENUM</field> + <field type="uint8_t" name="nav_mode">Navigation mode, see UALBERTA_NAV_MODE ENUM</field> + <field type="uint8_t" name="pilot">Pilot mode, see UALBERTA_PILOT_MODE</field> + </message> + </messages> +</mavlink>