diff --git a/Tools/ArdupilotMegaPlanner/APMPlannerXplanes/APMPlannerXplanes.suo b/Tools/ArdupilotMegaPlanner/APMPlannerXplanes/APMPlannerXplanes.suo index b1c251e075..47d8452c4b 100644 Binary files a/Tools/ArdupilotMegaPlanner/APMPlannerXplanes/APMPlannerXplanes.suo and b/Tools/ArdupilotMegaPlanner/APMPlannerXplanes/APMPlannerXplanes.suo differ diff --git a/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj b/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj index f15b7d9e87..51a7065b3b 100644 --- a/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj +++ b/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj @@ -349,6 +349,15 @@ AGauge.cs Designer + + Firmware.cs + + + FlightData.cs + + + Terminal.cs + Log.cs @@ -491,7 +500,9 @@ Always - + + Always + @@ -501,8 +512,12 @@ - - + + Always + + + Always + Always diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/Configuration.cs b/Tools/ArdupilotMegaPlanner/GCSViews/Configuration.cs index d411445607..baf9c0bb8e 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/Configuration.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/Configuration.cs @@ -138,7 +138,7 @@ namespace ArdupilotMega.GCSViews // setup language selection CultureInfo ci = null; - foreach (string name in new string[] { "en-US", "zh-Hans" }) + foreach (string name in new string[] { "en-US", "zh-Hans", "ru" }) { ci = MainV2.getcultureinfo(name); if (ci != null) diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/Firmware.cs b/Tools/ArdupilotMegaPlanner/GCSViews/Firmware.cs index 71408d070d..d24f7c0f12 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/Firmware.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/Firmware.cs @@ -695,6 +695,7 @@ namespace ArdupilotMega.GCSViews int optionoffset = 0; int total = 0; + bool hitend = false; while (!sr.EndOfStream) { @@ -726,11 +727,34 @@ namespace ArdupilotMega.GCSViews { optionoffset += (int)Convert.ToUInt16(line.Substring(9, 4), 16) << 4; } + else if (option == 1) + { + hitend = true; + } int checksum = Convert.ToInt32(line.Substring(line.Length - 2, 2), 16); + + byte checksumact = 0; + for (int z = 0; z < ((line.Length - 1 - 2) / 2) ; z++) // minus 1 for : then mins 2 for checksum itself + { + checksumact += Convert.ToByte(line.Substring(z * 2 + 1, 2), 16); + } + checksumact = (byte)(0x100 - checksumact); + + if (checksumact != checksum) + { + MessageBox.Show("The hex file loaded is invalid, please try again."); + throw new Exception("Checksum Failed - Invalid Hex"); + } } //Regex regex = new Regex(@"^:(..)(....)(..)(.*)(..)$"); // length - address - option - data - checksum } + if (!hitend) + { + MessageBox.Show("The hex file did no contain an end flag. aborting"); + throw new Exception("No end flag in file"); + } + Array.Resize(ref FLASH, total); return FLASH; diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.cs b/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.cs index 2aa13247c7..f74f23eb8d 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.cs @@ -1364,7 +1364,13 @@ namespace ArdupilotMega.GCSViews } } - TXT_DefaultAlt.Text = ((float)param["ALT_HOLD_RTL"] * MainV2.cs.multiplierdist).ToString("0"); + string hold_alt = ((float)param["ALT_HOLD_RTL"] * MainV2.cs.multiplierdist).ToString("0"); + + if (hold_alt != "-1") + { + TXT_DefaultAlt.Text = hold_alt; + } + TXT_WPRad.Text = ((float)param["WP_RADIUS"] * MainV2.cs.multiplierdist).ToString("0"); try { diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/Simulation.cs b/Tools/ArdupilotMegaPlanner/GCSViews/Simulation.cs index 2c0469d8ef..ccecf242f8 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/Simulation.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/Simulation.cs @@ -1555,6 +1555,16 @@ namespace ArdupilotMega.GCSViews ofd.InitialDirectory = @"C:\Program Files\FlightGear\bin\Win32\"; extra = " --fg-root=\"C:\\Program Files\\FlightGear\\data\""; } + else if (File.Exists(@"C:\Program Files\FlightGear 2.4.0\bin\Win32\fgfs.exe")) + { + ofd.InitialDirectory = @"C:\Program Files\FlightGear 2.4.0\bin\Win32\"; + extra = " --fg-root=\"C:\\Program Files\\FlightGear 2.4.0\\data\""; + } + else if (File.Exists(@"C:\Program Files (x86)\FlightGear 2.4.0\bin\Win32\fgfs.exe")) + { + ofd.InitialDirectory = @"C:\Program Files (x86)\FlightGear 2.4.0\bin\Win32\"; + extra = " --fg-root=\"C:\\Program Files (x86)\\FlightGear 2.4.0\\data\""; + } else if (File.Exists(@"/usr/games/fgfs")) { ofd.InitialDirectory = @"/usr/games"; diff --git a/Tools/ArdupilotMegaPlanner/MAVLinkTypes.cs b/Tools/ArdupilotMegaPlanner/MAVLinkTypes.cs index 12df0aab59..d5bae2043a 100644 --- a/Tools/ArdupilotMegaPlanner/MAVLinkTypes.cs +++ b/Tools/ArdupilotMegaPlanner/MAVLinkTypes.cs @@ -1,4 +1,6 @@ using System; +using System.Collections.Generic; +using System.Text; using System.Runtime.InteropServices; namespace ArdupilotMega @@ -11,8 +13,8 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_meminfo_t { - public ushort brkval; ///< heap top - public ushort freemem; ///< free memory + public ushort brkval; /// heap top + public ushort freemem; /// free memory }; public const byte MAVLINK_MSG_ID_MEMINFO_LEN = 4; @@ -21,18 +23,18 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_sensor_offsets_t { - public short mag_ofs_x; ///< magnetometer X offset - public short mag_ofs_y; ///< magnetometer Y offset - public short mag_ofs_z; ///< magnetometer Z offset - public float mag_declination; ///< magnetic declination (radians) - public int raw_press; ///< raw pressure from barometer - public int raw_temp; ///< raw temperature from barometer - public float gyro_cal_x; ///< gyro X calibration - public float gyro_cal_y; ///< gyro Y calibration - public float gyro_cal_z; ///< gyro Z calibration - public float accel_cal_x; ///< accel X calibration - public float accel_cal_y; ///< accel Y calibration - public float accel_cal_z; ///< accel Z calibration + public short mag_ofs_x; /// magnetometer X offset + public short mag_ofs_y; /// magnetometer Y offset + public short mag_ofs_z; /// magnetometer Z offset + public float mag_declination; /// magnetic declination (radians) + public int raw_press; /// raw pressure from barometer + public int raw_temp; /// raw temperature from barometer + public float gyro_cal_x; /// gyro X calibration + public float gyro_cal_y; /// gyro Y calibration + public float gyro_cal_z; /// gyro Z calibration + public float accel_cal_x; /// accel X calibration + public float accel_cal_y; /// accel Y calibration + public float accel_cal_z; /// accel Z calibration }; public const byte MAVLINK_MSG_ID_SENSOR_OFFSETS_LEN = 42; @@ -41,11 +43,11 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_set_mag_offsets_t { - public byte target_system; ///< System ID - public byte target_component; ///< Component ID - public short mag_ofs_x; ///< magnetometer X offset - public short mag_ofs_y; ///< magnetometer Y offset - public short mag_ofs_z; ///< magnetometer Z offset + public byte target_system; /// System ID + public byte target_component; /// Component ID + public short mag_ofs_x; /// magnetometer X offset + public short mag_ofs_y; /// magnetometer Y offset + public short mag_ofs_z; /// magnetometer Z offset }; public const byte MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN = 8; @@ -119,9 +121,9 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_action_t { - public byte target; ///< The system executing the action - public byte target_component; ///< The component executing the action - public byte action; ///< The action id + public byte target; /// The system executing the action + public byte target_component; /// The component executing the action + public byte action; /// The action id }; public const byte MAVLINK_MSG_ID_ACTION_LEN = 3; @@ -130,8 +132,8 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_action_ack_t { - public byte action; ///< The action id - public byte result; ///< 0: Action DENIED, 1: Action executed + public byte action; /// The action id + public byte result; /// 0: Action DENIED, 1: Action executed }; public const byte MAVLINK_MSG_ID_ACTION_ACK_LEN = 2; @@ -140,13 +142,13 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_attitude_t { - public ulong usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot) - public float roll; ///< Roll angle (rad) - public float pitch; ///< Pitch angle (rad) - public float yaw; ///< Yaw angle (rad) - public float rollspeed; ///< Roll angular speed (rad/s) - public float pitchspeed; ///< Pitch angular speed (rad/s) - public float yawspeed; ///< Yaw angular speed (rad/s) + public ulong usec; /// Timestamp (microseconds since UNIX epoch or microseconds since system boot) + public float roll; /// Roll angle (rad) + public float pitch; /// Pitch angle (rad) + public float yaw; /// Yaw angle (rad) + public float rollspeed; /// Roll angular speed (rad/s) + public float pitchspeed; /// Pitch angular speed (rad/s) + public float yawspeed; /// Yaw angular speed (rad/s) }; public const byte MAVLINK_MSG_ID_ATTITUDE_LEN = 32; @@ -155,11 +157,11 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_attitude_controller_output_t { - public byte enabled; ///< 1: enabled, 0: disabled - public byte roll; ///< Attitude roll: -128: -100%, 127: +100% - public byte pitch; ///< Attitude pitch: -128: -100%, 127: +100% - public byte yaw; ///< Attitude yaw: -128: -100%, 127: +100% - public byte thrust; ///< Attitude thrust: -128: -100%, 127: +100% + public byte enabled; /// 1: enabled, 0: disabled + public byte roll; /// Attitude roll: -128: -100%, 127: +100% + public byte pitch; /// Attitude pitch: -128: -100%, 127: +100% + public byte yaw; /// Attitude yaw: -128: -100%, 127: +100% + public byte thrust; /// Attitude thrust: -128: -100%, 127: +100% }; @@ -167,13 +169,13 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_attitude_new_t { - public ulong usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot) - public float roll; ///< Roll angle (rad) - public float pitch; ///< Pitch angle (rad) - public float yaw; ///< Yaw angle (rad) - public float rollspeed; ///< Roll angular speed (rad/s) - public float pitchspeed; ///< Pitch angular speed (rad/s) - public float yawspeed; ///< Yaw angular speed (rad/s) + public ulong usec; /// Timestamp (microseconds since UNIX epoch or microseconds since system boot) + public float roll; /// Roll angle (rad) + public float pitch; /// Pitch angle (rad) + public float yaw; /// Yaw angle (rad) + public float rollspeed; /// Roll angular speed (rad/s) + public float pitchspeed; /// Pitch angular speed (rad/s) + public float yawspeed; /// Yaw angular speed (rad/s) }; @@ -184,7 +186,7 @@ namespace ArdupilotMega [MarshalAs( UnmanagedType.ByValArray, SizeConst=32)] - char key; ///< key + char key; /// key }; public const byte MAVLINK_MSG_ID_AUTH_KEY_LEN = 32; @@ -193,7 +195,7 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_boot_t { - public uint version; ///< The onboard software version + public uint version; /// The onboard software version }; public const byte MAVLINK_MSG_ID_BOOT_LEN = 4; @@ -202,13 +204,13 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_change_operator_control_t { - public byte target_system; ///< System the GCS requests control for - public byte control_request; ///< 0: request control of this MAV, 1: Release control of this MAV - public byte 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. + public byte target_system; /// System the GCS requests control for + public byte control_request; /// 0: request control of this MAV, 1: Release control of this MAV + public byte 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. [MarshalAs( UnmanagedType.ByValArray, SizeConst=25)] - char 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 "!?,.-" + char 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 "!?,.-" }; public const byte MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN = 28; @@ -217,9 +219,9 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_change_operator_control_ack_t { - public byte gcs_system_id; ///< ID of the GCS this message - public byte control_request; ///< 0: request control of this MAV, 1: Release control of this MAV - public byte ack; ///< 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control + public byte gcs_system_id; /// ID of the GCS this message + public byte control_request; /// 0: request control of this MAV, 1: Release control of this MAV + public byte ack; /// 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control }; public const byte MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN = 3; @@ -228,14 +230,14 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_command_t { - public byte target_system; ///< System which should execute the command - public byte target_component; ///< Component which should execute the command, 0 for all components - public byte command; ///< Command ID, as defined by MAV_CMD enum. - public byte confirmation; ///< 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) - public float param1; ///< Parameter 1, as defined by MAV_CMD enum. - public float param2; ///< Parameter 2, as defined by MAV_CMD enum. - public float param3; ///< Parameter 3, as defined by MAV_CMD enum. - public float param4; ///< Parameter 4, as defined by MAV_CMD enum. + public byte target_system; /// System which should execute the command + public byte target_component; /// Component which should execute the command, 0 for all components + public byte command; /// Command ID, as defined by MAV_CMD enum. + public byte confirmation; /// 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) + public float param1; /// Parameter 1, as defined by MAV_CMD enum. + public float param2; /// Parameter 2, as defined by MAV_CMD enum. + public float param3; /// Parameter 3, as defined by MAV_CMD enum. + public float param4; /// Parameter 4, as defined by MAV_CMD enum. }; public const byte MAVLINK_MSG_ID_COMMAND_LEN = 20; @@ -244,8 +246,8 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_command_ack_t { - public float command; ///< Current airspeed in m/s - public float result; ///< 1: Action ACCEPTED and EXECUTED, 1: Action TEMPORARY REJECTED/DENIED, 2: Action PERMANENTLY DENIED, 3: Action UNKNOWN/UNSUPPORTED, 4: Requesting CONFIRMATION + public float command; /// Current airspeed in m/s + public float result; /// 1: Action ACCEPTED and EXECUTED, 1: Action TEMPORARY REJECTED/DENIED, 2: Action PERMANENTLY DENIED, 3: Action UNKNOWN/UNSUPPORTED, 4: Requesting CONFIRMATION }; public const byte MAVLINK_MSG_ID_COMMAND_ACK_LEN = 8; @@ -254,14 +256,14 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_control_status_t { - public byte position_fix; ///< Position fix: 0: lost, 2: 2D position fix, 3: 3D position fix - public byte vision_fix; ///< Vision position fix: 0: lost, 1: 2D local position hold, 2: 2D global position fix, 3: 3D global position fix - public byte gps_fix; ///< GPS position fix: 0: no reception, 1: Minimum 1 satellite, but no position fix, 2: 2D position fix, 3: 3D position fix - public byte ahrs_health; ///< Attitude estimation health: 0: poor, 255: excellent - public byte control_att; ///< 0: Attitude control disabled, 1: enabled - public byte control_pos_xy; ///< 0: X, Y position control disabled, 1: enabled - public byte control_pos_z; ///< 0: Z position control disabled, 1: enabled - public byte control_pos_yaw; ///< 0: Yaw angle control disabled, 1: enabled + public byte position_fix; /// Position fix: 0: lost, 2: 2D position fix, 3: 3D position fix + public byte vision_fix; /// Vision position fix: 0: lost, 1: 2D local position hold, 2: 2D global position fix, 3: 3D global position fix + public byte gps_fix; /// GPS position fix: 0: no reception, 1: Minimum 1 satellite, but no position fix, 2: 2D position fix, 3: 3D position fix + public byte ahrs_health; /// Attitude estimation health: 0: poor, 255: excellent + public byte control_att; /// 0: Attitude control disabled, 1: enabled + public byte control_pos_xy; /// 0: X, Y position control disabled, 1: enabled + public byte control_pos_z; /// 0: Z position control disabled, 1: enabled + public byte control_pos_yaw; /// 0: Yaw angle control disabled, 1: enabled }; public const byte MAVLINK_MSG_ID_CONTROL_STATUS_LEN = 8; @@ -270,8 +272,8 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_debug_t { - public byte ind; ///< index of debug variable - public float value; ///< DEBUG value + public byte ind; /// index of debug variable + public float value; /// DEBUG value }; public const byte MAVLINK_MSG_ID_DEBUG_LEN = 5; @@ -283,11 +285,11 @@ namespace ArdupilotMega [MarshalAs( UnmanagedType.ByValArray, SizeConst=10)] - char name; ///< Name - public ulong usec; ///< Timestamp - public float x; ///< x - public float y; ///< y - public float z; ///< z + char name; /// Name + public ulong usec; /// Timestamp + public float x; /// x + public float y; /// y + public float z; /// z }; public const byte MAVLINK_MSG_ID_DEBUG_VECT_LEN = 30; @@ -296,22 +298,22 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_full_state_t { - public ulong usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot) - public float roll; ///< Roll angle (rad) - public float pitch; ///< Pitch angle (rad) - public float yaw; ///< Yaw angle (rad) - public float rollspeed; ///< Roll angular speed (rad/s) - public float pitchspeed; ///< Pitch angular speed (rad/s) - public float yawspeed; ///< Yaw angular speed (rad/s) - public int lat; ///< Latitude, expressed as * 1E7 - public int lon; ///< Longitude, expressed as * 1E7 - public int alt; ///< Altitude in meters, expressed as * 1000 (millimeters) - public short vx; ///< Ground X Speed (Latitude), expressed as m/s * 100 - public short vy; ///< Ground Y Speed (Longitude), expressed as m/s * 100 - public short vz; ///< Ground Z Speed (Altitude), expressed as m/s * 100 - public short xacc; ///< X acceleration (mg) - public short yacc; ///< Y acceleration (mg) - public short zacc; ///< Z acceleration (mg) + public ulong usec; /// Timestamp (microseconds since UNIX epoch or microseconds since system boot) + public float roll; /// Roll angle (rad) + public float pitch; /// Pitch angle (rad) + public float yaw; /// Yaw angle (rad) + public float rollspeed; /// Roll angular speed (rad/s) + public float pitchspeed; /// Pitch angular speed (rad/s) + public float yawspeed; /// Yaw angular speed (rad/s) + public int lat; /// Latitude, expressed as * 1E7 + public int lon; /// Longitude, expressed as * 1E7 + public int alt; /// Altitude in meters, expressed as * 1000 (millimeters) + public short vx; /// Ground X Speed (Latitude), expressed as m/s * 100 + public short vy; /// Ground Y Speed (Longitude), expressed as m/s * 100 + public short vz; /// Ground Z Speed (Altitude), expressed as m/s * 100 + public short xacc; /// X acceleration (mg) + public short yacc; /// Y acceleration (mg) + public short zacc; /// Z acceleration (mg) }; @@ -319,13 +321,13 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_global_position_t { - public ulong usec; ///< Timestamp (microseconds since unix epoch) - public float lat; ///< Latitude, in degrees - public float lon; ///< Longitude, in degrees - public float alt; ///< Absolute altitude, in meters - public float vx; ///< X Speed (in Latitude direction, positive: going north) - public float vy; ///< Y Speed (in Longitude direction, positive: going east) - public float vz; ///< Z Speed (in Altitude direction, positive: going up) + public ulong usec; /// Timestamp (microseconds since unix epoch) + public float lat; /// Latitude, in degrees + public float lon; /// Longitude, in degrees + public float alt; /// Absolute altitude, in meters + public float vx; /// X Speed (in Latitude direction, positive: going north) + public float vy; /// Y Speed (in Longitude direction, positive: going east) + public float vz; /// Z Speed (in Altitude direction, positive: going up) }; public const byte MAVLINK_MSG_ID_GLOBAL_POSITION_LEN = 32; @@ -334,12 +336,12 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_global_position_int_t { - public int lat; ///< Latitude, expressed as * 1E7 - public int lon; ///< Longitude, expressed as * 1E7 - public int alt; ///< Altitude in meters, expressed as * 1000 (millimeters) - public short vx; ///< Ground X Speed (Latitude), expressed as m/s * 100 - public short vy; ///< Ground Y Speed (Longitude), expressed as m/s * 100 - public short vz; ///< Ground Z Speed (Altitude), expressed as m/s * 100 + public int lat; /// Latitude, expressed as * 1E7 + public int lon; /// Longitude, expressed as * 1E7 + public int alt; /// Altitude in meters, expressed as * 1000 (millimeters) + public short vx; /// Ground X Speed (Latitude), expressed as m/s * 100 + public short vy; /// Ground Y Speed (Longitude), expressed as m/s * 100 + public short vz; /// Ground Z Speed (Altitude), expressed as m/s * 100 }; public const byte MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN = 18; @@ -348,9 +350,9 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_gps_local_origin_set_t { - public int latitude; ///< Latitude (WGS84), expressed as * 1E7 - public int longitude; ///< Longitude (WGS84), expressed as * 1E7 - public int altitude; ///< Altitude(WGS84), expressed as * 1000 + public int latitude; /// Latitude (WGS84), expressed as * 1E7 + public int longitude; /// Longitude (WGS84), expressed as * 1E7 + public int altitude; /// Altitude(WGS84), expressed as * 1000 }; public const byte MAVLINK_MSG_ID_GPS_LOCAL_ORIGIN_SET_LEN = 12; @@ -359,15 +361,15 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_gps_raw_t { - public ulong usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot) - public byte 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. - public float lat; ///< Latitude in degrees - public float lon; ///< Longitude in degrees - public float alt; ///< Altitude in meters - public float eph; ///< GPS HDOP - public float epv; ///< GPS VDOP - public float v; ///< GPS ground speed - public float hdg; ///< Compass heading in degrees, 0..360 degrees + public ulong usec; /// Timestamp (microseconds since UNIX epoch or microseconds since system boot) + public byte 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. + public float lat; /// Latitude in degrees + public float lon; /// Longitude in degrees + public float alt; /// Altitude in meters + public float eph; /// GPS HDOP + public float epv; /// GPS VDOP + public float v; /// GPS ground speed + public float hdg; /// Compass heading in degrees, 0..360 degrees }; public const byte MAVLINK_MSG_ID_GPS_RAW_LEN = 37; @@ -376,15 +378,15 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_gps_raw_int_t { - public ulong usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot) - public byte 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. - public int lat; ///< Latitude in 1E7 degrees - public int lon; ///< Longitude in 1E7 degrees - public int alt; ///< Altitude in 1E3 meters (millimeters) - public float eph; ///< GPS HDOP - public float epv; ///< GPS VDOP - public float v; ///< GPS ground speed (m/s) - public float hdg; ///< Compass heading in degrees, 0..360 degrees + public ulong usec; /// Timestamp (microseconds since UNIX epoch or microseconds since system boot) + public byte 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. + public int lat; /// Latitude in 1E7 degrees + public int lon; /// Longitude in 1E7 degrees + public int alt; /// Altitude in 1E3 meters (millimeters) + public float eph; /// GPS HDOP + public float epv; /// GPS VDOP + public float v; /// GPS ground speed (m/s) + public float hdg; /// Compass heading in degrees, 0..360 degrees }; public const byte MAVLINK_MSG_ID_GPS_RAW_INT_LEN = 37; @@ -393,11 +395,11 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_gps_set_global_origin_t { - public byte target_system; ///< System ID - public byte target_component; ///< Component ID - public int latitude; ///< global position * 1E7 - public int longitude; ///< global position * 1E7 - public int altitude; ///< global position * 1000 + public byte target_system; /// System ID + public byte target_component; /// Component ID + public int latitude; /// global position * 1E7 + public int longitude; /// global position * 1E7 + public int altitude; /// global position * 1000 }; public const byte MAVLINK_MSG_ID_GPS_SET_GLOBAL_ORIGIN_LEN = 14; @@ -406,27 +408,27 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_gps_status_t { - public byte satellites_visible; ///< Number of satellites visible + public byte satellites_visible; /// Number of satellites visible [MarshalAs( UnmanagedType.ByValArray, SizeConst=20)] - public byte[] satellite_prn; ///< Global satellite ID + public byte[] satellite_prn; /// Global satellite ID [MarshalAs( UnmanagedType.ByValArray, SizeConst=20)] - public byte[] satellite_used; ///< 0: Satellite not used, 1: used for localization + public byte[] satellite_used; /// 0: Satellite not used, 1: used for localization [MarshalAs( UnmanagedType.ByValArray, SizeConst=20)] - public byte[] satellite_elevation; ///< Elevation (0: right on top of receiver, 90: on the horizon) of satellite + public byte[] satellite_elevation; /// Elevation (0: right on top of receiver, 90: on the horizon) of satellite [MarshalAs( UnmanagedType.ByValArray, SizeConst=20)] - public byte[] satellite_azimuth; ///< Direction of satellite, 0: 0 deg, 255: 360 deg. + public byte[] satellite_azimuth; /// Direction of satellite, 0: 0 deg, 255: 360 deg. [MarshalAs( UnmanagedType.ByValArray, SizeConst=20)] - public byte[] satellite_snr; ///< Signal to noise ratio of satellite + public byte[] satellite_snr; /// Signal to noise ratio of satellite }; public const byte MAVLINK_MSG_ID_GPS_STATUS_LEN = 101; @@ -435,9 +437,9 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_heartbeat_t { - public byte type; ///< Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) - public byte autopilot; ///< Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM - public byte mavlink_version; ///< MAVLink version + public byte type; /// Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) + public byte autopilot; /// Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM + public byte mavlink_version; /// MAVLink version }; public const byte MAVLINK_MSG_ID_HEARTBEAT_LEN = 3; @@ -446,13 +448,13 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_hil_controls_t { - public ulong time_us; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot) - public float roll_ailerons; ///< Control output -3 .. 1 - public float pitch_elevator; ///< Control output -1 .. 1 - public float yaw_rudder; ///< Control output -1 .. 1 - public float throttle; ///< Throttle 0 .. 1 - public byte mode; ///< System mode (MAV_MODE) - public byte nav_mode; ///< Navigation mode (MAV_NAV_MODE) + public ulong time_us; /// Timestamp (microseconds since UNIX epoch or microseconds since system boot) + public float roll_ailerons; /// Control output -3 .. 1 + public float pitch_elevator; /// Control output -1 .. 1 + public float yaw_rudder; /// Control output -1 .. 1 + public float throttle; /// Throttle 0 .. 1 + public byte mode; /// System mode (MAV_MODE) + public byte nav_mode; /// Navigation mode (MAV_NAV_MODE) }; public const byte MAVLINK_MSG_ID_HIL_CONTROLS_LEN = 26; @@ -461,22 +463,22 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_hil_state_t { - public ulong usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot) - public float roll; ///< Roll angle (rad) - public float pitch; ///< Pitch angle (rad) - public float yaw; ///< Yaw angle (rad) - public float rollspeed; ///< Roll angular speed (rad/s) - public float pitchspeed; ///< Pitch angular speed (rad/s) - public float yawspeed; ///< Yaw angular speed (rad/s) - public int lat; ///< Latitude, expressed as * 1E7 - public int lon; ///< Longitude, expressed as * 1E7 - public int alt; ///< Altitude in meters, expressed as * 1000 (millimeters) - public short vx; ///< Ground X Speed (Latitude), expressed as m/s * 100 - public short vy; ///< Ground Y Speed (Longitude), expressed as m/s * 100 - public short vz; ///< Ground Z Speed (Altitude), expressed as m/s * 100 - public short xacc; ///< X acceleration (mg) - public short yacc; ///< Y acceleration (mg) - public short zacc; ///< Z acceleration (mg) + public ulong usec; /// Timestamp (microseconds since UNIX epoch or microseconds since system boot) + public float roll; /// Roll angle (rad) + public float pitch; /// Pitch angle (rad) + public float yaw; /// Yaw angle (rad) + public float rollspeed; /// Roll angular speed (rad/s) + public float pitchspeed; /// Pitch angular speed (rad/s) + public float yawspeed; /// Yaw angular speed (rad/s) + public int lat; /// Latitude, expressed as * 1E7 + public int lon; /// Longitude, expressed as * 1E7 + public int alt; /// Altitude in meters, expressed as * 1000 (millimeters) + public short vx; /// Ground X Speed (Latitude), expressed as m/s * 100 + public short vy; /// Ground Y Speed (Longitude), expressed as m/s * 100 + public short vz; /// Ground Z Speed (Altitude), expressed as m/s * 100 + public short xacc; /// X acceleration (mg) + public short yacc; /// Y acceleration (mg) + public short zacc; /// Z acceleration (mg) }; public const byte MAVLINK_MSG_ID_HIL_STATE_LEN = 56; @@ -485,13 +487,13 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_local_position_t { - public ulong usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot) - public float x; ///< X Position - public float y; ///< Y Position - public float z; ///< Z Position - public float vx; ///< X Speed - public float vy; ///< Y Speed - public float vz; ///< Z Speed + public ulong usec; /// Timestamp (microseconds since UNIX epoch or microseconds since system boot) + public float x; /// X Position + public float y; /// Y Position + public float z; /// Z Position + public float vx; /// X Speed + public float vy; /// Y Speed + public float vz; /// Z Speed }; public const byte MAVLINK_MSG_ID_LOCAL_POSITION_LEN = 32; @@ -500,10 +502,10 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_local_position_setpoint_t { - public float x; ///< x position - public float y; ///< y position - public float z; ///< z position - public float yaw; ///< Desired yaw angle + public float x; /// x position + public float y; /// y position + public float z; /// z position + public float yaw; /// Desired yaw angle }; public const byte MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_LEN = 16; @@ -512,12 +514,12 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_local_position_setpoint_set_t { - public byte target_system; ///< System ID - public byte target_component; ///< Component ID - public float x; ///< x position - public float y; ///< y position - public float z; ///< z position - public float yaw; ///< Desired yaw angle + public byte target_system; /// System ID + public byte target_component; /// Component ID + public float x; /// x position + public float y; /// y position + public float z; /// z position + public float yaw; /// Desired yaw angle }; public const byte MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_SET_LEN = 18; @@ -526,15 +528,15 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_manual_control_t { - public byte target; ///< The system to be controlled - public float roll; ///< roll - public float pitch; ///< pitch - public float yaw; ///< yaw - public float thrust; ///< thrust - public byte roll_manual; ///< roll control enabled auto:0, manual:1 - public byte pitch_manual; ///< pitch auto:0, manual:1 - public byte yaw_manual; ///< yaw auto:0, manual:1 - public byte thrust_manual; ///< thrust auto:0, manual:1 + public byte target; /// The system to be controlled + public float roll; /// roll + public float pitch; /// pitch + public float yaw; /// yaw + public float thrust; /// thrust + public byte roll_manual; /// roll control enabled auto:0, manual:1 + public byte pitch_manual; /// pitch auto:0, manual:1 + public byte yaw_manual; /// yaw auto:0, manual:1 + public byte thrust_manual; /// thrust auto:0, manual:1 }; public const byte MAVLINK_MSG_ID_MANUAL_CONTROL_LEN = 21; @@ -546,8 +548,8 @@ namespace ArdupilotMega [MarshalAs( UnmanagedType.ByValArray, SizeConst=10)] - char name; ///< Name of the debug variable - public float value; ///< Floating point value + char name; /// Name of the debug variable + public float value; /// Floating point value }; public const byte MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN = 14; @@ -559,8 +561,8 @@ namespace ArdupilotMega [MarshalAs( UnmanagedType.ByValArray, SizeConst=10)] - char name; ///< Name of the debug variable - public int value; ///< Signed integer value + char name; /// Name of the debug variable + public int value; /// Signed integer value }; public const byte MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN = 14; @@ -569,14 +571,14 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_nav_controller_output_t { - public float nav_roll; ///< Current desired roll in degrees - public float nav_pitch; ///< Current desired pitch in degrees - public short nav_bearing; ///< Current desired heading in degrees - public short target_bearing; ///< Bearing to current waypoint/target in degrees - public ushort wp_dist; ///< Distance to active waypoint in meters - public float alt_error; ///< Current altitude error in meters - public float aspd_error; ///< Current airspeed error in meters/second - public float xtrack_error; ///< Current crosstrack error on x-y plane in meters + public float nav_roll; /// Current desired roll in degrees + public float nav_pitch; /// Current desired pitch in degrees + public short nav_bearing; /// Current desired heading in degrees + public short target_bearing; /// Bearing to current waypoint/target in degrees + public ushort wp_dist; /// Distance to active waypoint in meters + public float alt_error; /// Current altitude error in meters + public float aspd_error; /// Current airspeed error in meters/second + public float xtrack_error; /// Current crosstrack error on x-y plane in meters }; public const byte MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN = 26; @@ -585,16 +587,16 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_object_detection_event_t { - public uint time; ///< Timestamp in milliseconds since system boot - public ushort object_id; ///< Object ID - public byte type; ///< Object type: 0: image, 1: letter, 2: ground vehicle, 3: air vehicle, 4: surface vehicle, 5: sub-surface vehicle, 6: human, 7: animal + public uint time; /// Timestamp in milliseconds since system boot + public ushort object_id; /// Object ID + public byte type; /// Object type: 0: image, 1: letter, 2: ground vehicle, 3: air vehicle, 4: surface vehicle, 5: sub-surface vehicle, 6: human, 7: animal [MarshalAs( UnmanagedType.ByValArray, SizeConst=20)] - char name; ///< Name of the object as defined by the detector - public byte quality; ///< Detection quality / confidence. 0: bad, 255: maximum confidence - public float bearing; ///< Angle of the object with respect to the body frame in NED coordinates in radians. 0: front - public float distance; ///< Ground distance in meters + char name; /// Name of the object as defined by the detector + public byte quality; /// Detection quality / confidence. 0: bad, 255: maximum confidence + public float bearing; /// Angle of the object with respect to the body frame in NED coordinates in radians. 0: front + public float distance; /// Ground distance in meters }; public const byte MAVLINK_MSG_ID_OBJECT_DETECTION_EVENT_LEN = 36; @@ -603,12 +605,12 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_optical_flow_t { - public ulong time; ///< Timestamp (UNIX) - public byte sensor_id; ///< Sensor ID - public short flow_x; ///< Flow in pixels in x-sensor direction - public short flow_y; ///< Flow in pixels in y-sensor direction - public byte quality; ///< Optical flow quality / confidence. 0: bad, 255: maximum quality - public float ground_distance; ///< Ground distance in meters + public ulong time; /// Timestamp (UNIX) + public byte sensor_id; /// Sensor ID + public short flow_x; /// Flow in pixels in x-sensor direction + public short flow_y; /// Flow in pixels in y-sensor direction + public byte quality; /// Optical flow quality / confidence. 0: bad, 255: maximum quality + public float ground_distance; /// Ground distance in meters }; public const byte MAVLINK_MSG_ID_OPTICAL_FLOW_LEN = 18; @@ -617,8 +619,8 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_param_request_list_t { - public byte target_system; ///< System ID - public byte target_component; ///< Component ID + public byte target_system; /// System ID + public byte target_component; /// Component ID }; public const byte MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN = 2; @@ -627,13 +629,13 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_param_request_read_t { - public byte target_system; ///< System ID - public byte target_component; ///< Component ID + public byte target_system; /// System ID + public byte target_component; /// Component ID [MarshalAs( UnmanagedType.ByValArray, SizeConst=15)] - public byte[] param_id; ///< Onboard parameter id - public short param_index; ///< Parameter index. Send -1 to use the param ID field as identifier + public byte[] param_id; /// Onboard parameter id + public short param_index; /// Parameter index. Send -1 to use the param ID field as identifier }; public const byte MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN = 19; @@ -642,13 +644,13 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_param_set_t { - public byte target_system; ///< System ID - public byte target_component; ///< Component ID + public byte target_system; /// System ID + public byte target_component; /// Component ID [MarshalAs( UnmanagedType.ByValArray, SizeConst=15)] - public byte[] param_id; ///< Onboard parameter id - public float param_value; ///< Onboard parameter value + public byte[] param_id; /// Onboard parameter id + public float param_value; /// Onboard parameter value }; public const byte MAVLINK_MSG_ID_PARAM_SET_LEN = 21; @@ -660,10 +662,10 @@ namespace ArdupilotMega [MarshalAs( UnmanagedType.ByValArray, SizeConst=15)] - public byte[] param_id; ///< Onboard parameter id - public float param_value; ///< Onboard parameter value - public ushort param_count; ///< Total number of onboard parameters - public ushort param_index; ///< Index of this onboard parameter + public byte[] param_id; /// Onboard parameter id + public float param_value; /// Onboard parameter value + public ushort param_count; /// Total number of onboard parameters + public ushort param_index; /// Index of this onboard parameter }; public const byte MAVLINK_MSG_ID_PARAM_VALUE_LEN = 23; @@ -672,10 +674,10 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_ping_t { - public uint seq; ///< PING sequence - public byte 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 - public byte 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 - public ulong time; ///< Unix timestamp in microseconds + public uint seq; /// PING sequence + public byte 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 + public byte 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 + public ulong time; /// Unix timestamp in microseconds }; public const byte MAVLINK_MSG_ID_PING_LEN = 14; @@ -684,11 +686,11 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_position_controller_output_t { - public byte enabled; ///< 1: enabled, 0: disabled - public byte x; ///< Position x: -128: -100%, 127: +100% - public byte y; ///< Position y: -128: -100%, 127: +100% - public byte z; ///< Position z: -128: -100%, 127: +100% - public byte yaw; ///< Position yaw: -128: -100%, 127: +100% + public byte enabled; /// 1: enabled, 0: disabled + public byte x; /// Position x: -128: -100%, 127: +100% + public byte y; /// Position y: -128: -100%, 127: +100% + public byte z; /// Position z: -128: -100%, 127: +100% + public byte yaw; /// Position yaw: -128: -100%, 127: +100% }; @@ -696,10 +698,10 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_position_target_t { - public float x; ///< x position - public float y; ///< y position - public float z; ///< z position - public float yaw; ///< yaw orientation in radians, 0 = NORTH + public float x; /// x position + public float y; /// y position + public float z; /// z position + public float yaw; /// yaw orientation in radians, 0 = NORTH }; public const byte MAVLINK_MSG_ID_POSITION_TARGET_LEN = 16; @@ -708,16 +710,16 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_raw_imu_t { - public ulong usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot) - public short xacc; ///< X acceleration (raw) - public short yacc; ///< Y acceleration (raw) - public short zacc; ///< Z acceleration (raw) - public short xgyro; ///< Angular speed around X axis (raw) - public short ygyro; ///< Angular speed around Y axis (raw) - public short zgyro; ///< Angular speed around Z axis (raw) - public short xmag; ///< X Magnetic field (raw) - public short ymag; ///< Y Magnetic field (raw) - public short zmag; ///< Z Magnetic field (raw) + public ulong usec; /// Timestamp (microseconds since UNIX epoch or microseconds since system boot) + public short xacc; /// X acceleration (raw) + public short yacc; /// Y acceleration (raw) + public short zacc; /// Z acceleration (raw) + public short xgyro; /// Angular speed around X axis (raw) + public short ygyro; /// Angular speed around Y axis (raw) + public short zgyro; /// Angular speed around Z axis (raw) + public short xmag; /// X Magnetic field (raw) + public short ymag; /// Y Magnetic field (raw) + public short zmag; /// Z Magnetic field (raw) }; public const byte MAVLINK_MSG_ID_RAW_IMU_LEN = 26; @@ -726,11 +728,11 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_raw_pressure_t { - public ulong usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot) - public short press_abs; ///< Absolute pressure (raw) - public short press_diff1; ///< Differential pressure 1 (raw) - public short press_diff2; ///< Differential pressure 2 (raw) - public short temperature; ///< Raw Temperature measurement (raw) + public ulong usec; /// Timestamp (microseconds since UNIX epoch or microseconds since system boot) + public short press_abs; /// Absolute pressure (raw) + public short press_diff1; /// Differential pressure 1 (raw) + public short press_diff2; /// Differential pressure 2 (raw) + public short temperature; /// Raw Temperature measurement (raw) }; public const byte MAVLINK_MSG_ID_RAW_PRESSURE_LEN = 16; @@ -739,16 +741,16 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_rc_channels_override_t { - public byte target_system; ///< System ID - public byte target_component; ///< Component ID - public ushort chan1_raw; ///< RC channel 1 value, in microseconds - public ushort chan2_raw; ///< RC channel 2 value, in microseconds - public ushort chan3_raw; ///< RC channel 3 value, in microseconds - public ushort chan4_raw; ///< RC channel 4 value, in microseconds - public ushort chan5_raw; ///< RC channel 5 value, in microseconds - public ushort chan6_raw; ///< RC channel 6 value, in microseconds - public ushort chan7_raw; ///< RC channel 7 value, in microseconds - public ushort chan8_raw; ///< RC channel 8 value, in microseconds + public byte target_system; /// System ID + public byte target_component; /// Component ID + public ushort chan1_raw; /// RC channel 1 value, in microseconds + public ushort chan2_raw; /// RC channel 2 value, in microseconds + public ushort chan3_raw; /// RC channel 3 value, in microseconds + public ushort chan4_raw; /// RC channel 4 value, in microseconds + public ushort chan5_raw; /// RC channel 5 value, in microseconds + public ushort chan6_raw; /// RC channel 6 value, in microseconds + public ushort chan7_raw; /// RC channel 7 value, in microseconds + public ushort chan8_raw; /// RC channel 8 value, in microseconds }; public const byte MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN = 18; @@ -757,15 +759,15 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_rc_channels_raw_t { - public ushort chan1_raw; ///< RC channel 1 value, in microseconds - public ushort chan2_raw; ///< RC channel 2 value, in microseconds - public ushort chan3_raw; ///< RC channel 3 value, in microseconds - public ushort chan4_raw; ///< RC channel 4 value, in microseconds - public ushort chan5_raw; ///< RC channel 5 value, in microseconds - public ushort chan6_raw; ///< RC channel 6 value, in microseconds - public ushort chan7_raw; ///< RC channel 7 value, in microseconds - public ushort chan8_raw; ///< RC channel 8 value, in microseconds - public byte rssi; ///< Receive signal strength indicator, 0: 0%, 255: 100% + public ushort chan1_raw; /// RC channel 1 value, in microseconds + public ushort chan2_raw; /// RC channel 2 value, in microseconds + public ushort chan3_raw; /// RC channel 3 value, in microseconds + public ushort chan4_raw; /// RC channel 4 value, in microseconds + public ushort chan5_raw; /// RC channel 5 value, in microseconds + public ushort chan6_raw; /// RC channel 6 value, in microseconds + public ushort chan7_raw; /// RC channel 7 value, in microseconds + public ushort chan8_raw; /// RC channel 8 value, in microseconds + public byte rssi; /// Receive signal strength indicator, 0: 0%, 255: 100% }; public const byte MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN = 17; @@ -774,15 +776,15 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_rc_channels_scaled_t { - public short chan1_scaled; ///< RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 - public short chan2_scaled; ///< RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 - public short chan3_scaled; ///< RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 - public short chan4_scaled; ///< RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 - public short chan5_scaled; ///< RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 - public short chan6_scaled; ///< RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 - public short chan7_scaled; ///< RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 - public short chan8_scaled; ///< RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 - public byte rssi; ///< Receive signal strength indicator, 0: 0%, 255: 100% + public short chan1_scaled; /// RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + public short chan2_scaled; /// RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + public short chan3_scaled; /// RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + public short chan4_scaled; /// RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + public short chan5_scaled; /// RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + public short chan6_scaled; /// RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + public short chan7_scaled; /// RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + public short chan8_scaled; /// RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 + public byte rssi; /// Receive signal strength indicator, 0: 0%, 255: 100% }; public const byte MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN = 17; @@ -791,11 +793,11 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_request_data_stream_t { - public byte target_system; ///< The target requested to send the message stream. - public byte target_component; ///< The target requested to send the message stream. - public byte req_stream_id; ///< The ID of the requested message type - public ushort req_message_rate; ///< Update rate in Hertz - public byte start_stop; ///< 1 to start sending, 0 to stop sending. + public byte target_system; /// The target requested to send the message stream. + public byte target_component; /// The target requested to send the message stream. + public byte req_stream_id; /// The ID of the requested message type + public ushort req_message_rate; /// Update rate in Hertz + public byte start_stop; /// 1 to start sending, 0 to stop sending. }; public const byte MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN = 6; @@ -804,11 +806,11 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_request_dynamic_gyro_calibration_t { - public byte target_system; ///< The system which should auto-calibrate - public byte target_component; ///< The system component which should auto-calibrate - public float mode; ///< The current ground-truth rpm - public byte axis; ///< The axis to calibrate: 0 roll, 1 pitch, 2 yaw - public ushort time; ///< The time to average over in ms + public byte target_system; /// The system which should auto-calibrate + public byte target_component; /// The system component which should auto-calibrate + public float mode; /// The current ground-truth rpm + public byte axis; /// The axis to calibrate: 0 roll, 1 pitch, 2 yaw + public ushort time; /// The time to average over in ms }; @@ -816,9 +818,9 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_request_static_calibration_t { - public byte target_system; ///< The system which should auto-calibrate - public byte target_component; ///< The system component which should auto-calibrate - public ushort time; ///< The time to average over in ms + public byte target_system; /// The system which should auto-calibrate + public byte target_component; /// The system component which should auto-calibrate + public ushort time; /// The time to average over in ms }; @@ -826,11 +828,11 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_roll_pitch_yaw_speed_thrust_setpoint_t { - public ulong time_us; ///< Timestamp in micro seconds since unix epoch - public float roll_speed; ///< Desired roll angular speed in rad/s - public float pitch_speed; ///< Desired pitch angular speed in rad/s - public float yaw_speed; ///< Desired yaw angular speed in rad/s - public float thrust; ///< Collective thrust, normalized to 0 .. 1 + public ulong time_us; /// Timestamp in micro seconds since unix epoch + public float roll_speed; /// Desired roll angular speed in rad/s + public float pitch_speed; /// Desired pitch angular speed in rad/s + public float yaw_speed; /// Desired yaw angular speed in rad/s + public float thrust; /// Collective thrust, normalized to 0 .. 1 }; public const byte MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT_LEN = 24; @@ -839,11 +841,11 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_roll_pitch_yaw_thrust_setpoint_t { - public ulong time_us; ///< Timestamp in micro seconds since unix epoch - public float roll; ///< Desired roll angle in radians - public float pitch; ///< Desired pitch angle in radians - public float yaw; ///< Desired yaw angle in radians - public float thrust; ///< Collective thrust, normalized to 0 .. 1 + public ulong time_us; /// Timestamp in micro seconds since unix epoch + public float roll; /// Desired roll angle in radians + public float pitch; /// Desired pitch angle in radians + public float yaw; /// Desired yaw angle in radians + public float thrust; /// Collective thrust, normalized to 0 .. 1 }; public const byte MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT_LEN = 24; @@ -852,13 +854,13 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_safety_allowed_area_t { - public byte 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. - public float p1x; ///< x position 1 / Latitude 1 - public float p1y; ///< y position 1 / Longitude 1 - public float p1z; ///< z position 1 / Altitude 1 - public float p2x; ///< x position 2 / Latitude 2 - public float p2y; ///< y position 2 / Longitude 2 - public float p2z; ///< z position 2 / Altitude 2 + public byte 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. + public float p1x; /// x position 1 / Latitude 1 + public float p1y; /// y position 1 / Longitude 1 + public float p1z; /// z position 1 / Altitude 1 + public float p2x; /// x position 2 / Latitude 2 + public float p2y; /// y position 2 / Longitude 2 + public float p2z; /// z position 2 / Altitude 2 }; public const byte MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN = 25; @@ -867,15 +869,15 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_safety_set_allowed_area_t { - public byte target_system; ///< System ID - public byte target_component; ///< Component ID - public byte 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. - public float p1x; ///< x position 1 / Latitude 1 - public float p1y; ///< y position 1 / Longitude 1 - public float p1z; ///< z position 1 / Altitude 1 - public float p2x; ///< x position 2 / Latitude 2 - public float p2y; ///< y position 2 / Longitude 2 - public float p2z; ///< z position 2 / Altitude 2 + public byte target_system; /// System ID + public byte target_component; /// Component ID + public byte 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. + public float p1x; /// x position 1 / Latitude 1 + public float p1y; /// y position 1 / Longitude 1 + public float p1z; /// z position 1 / Altitude 1 + public float p2x; /// x position 2 / Latitude 2 + public float p2y; /// y position 2 / Longitude 2 + public float p2z; /// z position 2 / Altitude 2 }; public const byte MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN = 27; @@ -884,16 +886,16 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_scaled_imu_t { - public ulong usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot) - public short xacc; ///< X acceleration (mg) - public short yacc; ///< Y acceleration (mg) - public short zacc; ///< Z acceleration (mg) - public short xgyro; ///< Angular speed around X axis (millirad /sec) - public short ygyro; ///< Angular speed around Y axis (millirad /sec) - public short zgyro; ///< Angular speed around Z axis (millirad /sec) - public short xmag; ///< X Magnetic field (milli tesla) - public short ymag; ///< Y Magnetic field (milli tesla) - public short zmag; ///< Z Magnetic field (milli tesla) + public ulong usec; /// Timestamp (microseconds since UNIX epoch or microseconds since system boot) + public short xacc; /// X acceleration (mg) + public short yacc; /// Y acceleration (mg) + public short zacc; /// Z acceleration (mg) + public short xgyro; /// Angular speed around X axis (millirad /sec) + public short ygyro; /// Angular speed around Y axis (millirad /sec) + public short zgyro; /// Angular speed around Z axis (millirad /sec) + public short xmag; /// X Magnetic field (milli tesla) + public short ymag; /// Y Magnetic field (milli tesla) + public short zmag; /// Z Magnetic field (milli tesla) }; public const byte MAVLINK_MSG_ID_SCALED_IMU_LEN = 26; @@ -902,10 +904,10 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_scaled_pressure_t { - public ulong usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot) - public float press_abs; ///< Absolute pressure (hectopascal) - public float press_diff; ///< Differential pressure 1 (hectopascal) - public short temperature; ///< Temperature measurement (0.01 degrees celsius) + public ulong usec; /// Timestamp (microseconds since UNIX epoch or microseconds since system boot) + public float press_abs; /// Absolute pressure (hectopascal) + public float press_diff; /// Differential pressure 1 (hectopascal) + public short temperature; /// Temperature measurement (0.01 degrees celsius) }; public const byte MAVLINK_MSG_ID_SCALED_PRESSURE_LEN = 18; @@ -914,14 +916,14 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_servo_output_raw_t { - public ushort servo1_raw; ///< Servo output 1 value, in microseconds - public ushort servo2_raw; ///< Servo output 2 value, in microseconds - public ushort servo3_raw; ///< Servo output 3 value, in microseconds - public ushort servo4_raw; ///< Servo output 4 value, in microseconds - public ushort servo5_raw; ///< Servo output 5 value, in microseconds - public ushort servo6_raw; ///< Servo output 6 value, in microseconds - public ushort servo7_raw; ///< Servo output 7 value, in microseconds - public ushort servo8_raw; ///< Servo output 8 value, in microseconds + public ushort servo1_raw; /// Servo output 1 value, in microseconds + public ushort servo2_raw; /// Servo output 2 value, in microseconds + public ushort servo3_raw; /// Servo output 3 value, in microseconds + public ushort servo4_raw; /// Servo output 4 value, in microseconds + public ushort servo5_raw; /// Servo output 5 value, in microseconds + public ushort servo6_raw; /// Servo output 6 value, in microseconds + public ushort servo7_raw; /// Servo output 7 value, in microseconds + public ushort servo8_raw; /// Servo output 8 value, in microseconds }; public const byte MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN = 16; @@ -930,8 +932,8 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_set_altitude_t { - public byte target; ///< The system setting the altitude - public uint mode; ///< The new altitude in meters + public byte target; /// The system setting the altitude + public uint mode; /// The new altitude in meters }; public const byte MAVLINK_MSG_ID_SET_ALTITUDE_LEN = 5; @@ -940,8 +942,8 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_set_mode_t { - public byte target; ///< The system setting the mode - public byte mode; ///< The new mode + public byte target; /// The system setting the mode + public byte mode; /// The new mode }; public const byte MAVLINK_MSG_ID_SET_MODE_LEN = 2; @@ -950,8 +952,8 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_set_nav_mode_t { - public byte target; ///< The system setting the mode - public byte nav_mode; ///< The new navigation mode + public byte target; /// The system setting the mode + public byte nav_mode; /// The new navigation mode }; public const byte MAVLINK_MSG_ID_SET_NAV_MODE_LEN = 2; @@ -960,11 +962,11 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_set_roll_pitch_yaw_t { - public byte target_system; ///< System ID - public byte target_component; ///< Component ID - public float roll; ///< Desired roll angle in radians - public float pitch; ///< Desired pitch angle in radians - public float yaw; ///< Desired yaw angle in radians + public byte target_system; /// System ID + public byte target_component; /// Component ID + public float roll; /// Desired roll angle in radians + public float pitch; /// Desired pitch angle in radians + public float yaw; /// Desired yaw angle in radians }; @@ -972,11 +974,11 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_set_roll_pitch_yaw_speed_t { - public byte target_system; ///< System ID - public byte target_component; ///< Component ID - public float roll_speed; ///< Desired roll angular speed in rad/s - public float pitch_speed; ///< Desired pitch angular speed in rad/s - public float yaw_speed; ///< Desired yaw angular speed in rad/s + public byte target_system; /// System ID + public byte target_component; /// Component ID + public float roll_speed; /// Desired roll angular speed in rad/s + public float pitch_speed; /// Desired pitch angular speed in rad/s + public float yaw_speed; /// Desired yaw angular speed in rad/s }; @@ -984,12 +986,12 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_set_roll_pitch_yaw_speed_thrust_t { - public byte target_system; ///< System ID - public byte target_component; ///< Component ID - public float roll_speed; ///< Desired roll angular speed in rad/s - public float pitch_speed; ///< Desired pitch angular speed in rad/s - public float yaw_speed; ///< Desired yaw angular speed in rad/s - public float thrust; ///< Collective thrust, normalized to 0 .. 1 + public byte target_system; /// System ID + public byte target_component; /// Component ID + public float roll_speed; /// Desired roll angular speed in rad/s + public float pitch_speed; /// Desired pitch angular speed in rad/s + public float yaw_speed; /// Desired yaw angular speed in rad/s + public float thrust; /// Collective thrust, normalized to 0 .. 1 }; public const byte MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST_LEN = 18; @@ -998,12 +1000,12 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_set_roll_pitch_yaw_thrust_t { - public byte target_system; ///< System ID - public byte target_component; ///< Component ID - public float roll; ///< Desired roll angle in radians - public float pitch; ///< Desired pitch angle in radians - public float yaw; ///< Desired yaw angle in radians - public float thrust; ///< Collective thrust, normalized to 0 .. 1 + public byte target_system; /// System ID + public byte target_component; /// Component ID + public float roll; /// Desired roll angle in radians + public float pitch; /// Desired pitch angle in radians + public float yaw; /// Desired yaw angle in radians + public float thrust; /// Collective thrust, normalized to 0 .. 1 }; public const byte MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST_LEN = 18; @@ -1012,15 +1014,15 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_state_correction_t { - public float xErr; ///< x position error - public float yErr; ///< y position error - public float zErr; ///< z position error - public float rollErr; ///< roll error (radians) - public float pitchErr; ///< pitch error (radians) - public float yawErr; ///< yaw error (radians) - public float vxErr; ///< x velocity - public float vyErr; ///< y velocity - public float vzErr; ///< z velocity + public float xErr; /// x position error + public float yErr; /// y position error + public float zErr; /// z position error + public float rollErr; /// roll error (radians) + public float pitchErr; /// pitch error (radians) + public float yawErr; /// yaw error (radians) + public float vxErr; /// x velocity + public float vyErr; /// y velocity + public float vzErr; /// z velocity }; public const byte MAVLINK_MSG_ID_STATE_CORRECTION_LEN = 36; @@ -1029,11 +1031,11 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_statustext_t { - public byte severity; ///< Severity of status, 0 = info message, 255 = critical fault + public byte severity; /// Severity of status, 0 = info message, 255 = critical fault [MarshalAs( UnmanagedType.ByValArray, SizeConst=50)] - public byte[] text; ///< Status text message, without null termination character + public byte[] text; /// Status text message, without null termination character }; public const byte MAVLINK_MSG_ID_STATUSTEXT_LEN = 51; @@ -1044,13 +1046,13 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_sys_status_t { - public byte mode; ///< System mode, see MAV_MODE ENUM in mavlink/include/mavlink_types.h - public byte nav_mode; ///< Navigation mode, see MAV_NAV_MODE ENUM - public byte status; ///< System status flag, see MAV_STATUS ENUM - public ushort load; ///< Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 - public ushort vbat; ///< Battery voltage, in millivolts (1 = 1 millivolt) - public ushort battery_remaining; ///< Remaining battery energy: (0%: 0, 100%: 1000) - public ushort packet_drop; ///< Dropped packets (packets that were corrupted on reception on the MAV) + public byte mode; /// System mode, see MAV_MODE ENUM in mavlink/include/mavlink_types.h + public byte nav_mode; /// Navigation mode, see MAV_NAV_MODE ENUM + public byte status; /// System status flag, see MAV_STATUS ENUM + public ushort load; /// Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 + public ushort vbat; /// Battery voltage, in millivolts (1 = 1 millivolt) + public ushort battery_remaining; /// Remaining battery energy: (0%: 0, 100%: 1000) + public ushort packet_drop; /// Dropped packets (packets that were corrupted on reception on the MAV) }; public const byte MAVLINK_MSG_ID_SYS_STATUS_LEN = 11; @@ -1059,12 +1061,12 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_vfr_hud_t { - public float airspeed; ///< Current airspeed in m/s - public float groundspeed; ///< Current ground speed in m/s - public short heading; ///< Current heading in degrees, in compass units (0..360, 0=north) - public ushort throttle; ///< Current throttle setting in integer percent, 0 to 100 - public float alt; ///< Current altitude (MSL), in meters - public float climb; ///< Current climb rate in meters/second + public float airspeed; /// Current airspeed in m/s + public float groundspeed; /// Current ground speed in m/s + public short heading; /// Current heading in degrees, in compass units (0..360, 0=north) + public ushort throttle; /// Current throttle setting in integer percent, 0 to 100 + public float alt; /// Current altitude (MSL), in meters + public float climb; /// Current climb rate in meters/second }; public const byte MAVLINK_MSG_ID_VFR_HUD_LEN = 20; @@ -1073,20 +1075,20 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_waypoint_t { - public byte target_system; ///< System ID - public byte target_component; ///< Component ID - public ushort seq; ///< Sequence - public byte frame; ///< The coordinate system of the waypoint. see MAV_FRAME in mavlink_types.h - public byte command; ///< The scheduled action for the waypoint. see MAV_COMMAND in common.xml MAVLink specs - public byte current; ///< false:0, true:1 - public byte autocontinue; ///< autocontinue to next wp - public float param1; ///< PARAM1 / For NAV command waypoints: Radius in which the waypoint is accepted as reached, in meters - public float param2; ///< PARAM2 / For NAV command waypoints: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds - public float 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. - public float param4; ///< PARAM4 / For NAV and LOITER command waypoints: Yaw orientation in degrees, [0..360] 0 = NORTH - public float x; ///< PARAM5 / local: x position, global: latitude - public float y; ///< PARAM6 / y position: global: longitude - public float z; ///< PARAM7 / z position: global: altitude + public byte target_system; /// System ID + public byte target_component; /// Component ID + public ushort seq; /// Sequence + public byte frame; /// The coordinate system of the waypoint. see MAV_FRAME in mavlink_types.h + public byte command; /// The scheduled action for the waypoint. see MAV_COMMAND in common.xml MAVLink specs + public byte current; /// false:0, true:1 + public byte autocontinue; /// autocontinue to next wp + public float param1; /// PARAM1 / For NAV command waypoints: Radius in which the waypoint is accepted as reached, in meters + public float param2; /// PARAM2 / For NAV command waypoints: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds + public float 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. + public float param4; /// PARAM4 / For NAV and LOITER command waypoints: Yaw orientation in degrees, [0..360] 0 = NORTH + public float x; /// PARAM5 / local: x position, global: latitude + public float y; /// PARAM6 / y position: global: longitude + public float z; /// PARAM7 / z position: global: altitude }; public const byte MAVLINK_MSG_ID_WAYPOINT_LEN = 36; @@ -1095,9 +1097,9 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_waypoint_ack_t { - public byte target_system; ///< System ID - public byte target_component; ///< Component ID - public byte type; ///< 0: OK, 1: Error + public byte target_system; /// System ID + public byte target_component; /// Component ID + public byte type; /// 0: OK, 1: Error }; public const byte MAVLINK_MSG_ID_WAYPOINT_ACK_LEN = 3; @@ -1106,8 +1108,8 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_waypoint_clear_all_t { - public byte target_system; ///< System ID - public byte target_component; ///< Component ID + public byte target_system; /// System ID + public byte target_component; /// Component ID }; public const byte MAVLINK_MSG_ID_WAYPOINT_CLEAR_ALL_LEN = 2; @@ -1116,9 +1118,9 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_waypoint_count_t { - public byte target_system; ///< System ID - public byte target_component; ///< Component ID - public ushort count; ///< Number of Waypoints in the Sequence + public byte target_system; /// System ID + public byte target_component; /// Component ID + public ushort count; /// Number of Waypoints in the Sequence }; public const byte MAVLINK_MSG_ID_WAYPOINT_COUNT_LEN = 4; @@ -1127,7 +1129,7 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_waypoint_current_t { - public ushort seq; ///< Sequence + public ushort seq; /// Sequence }; public const byte MAVLINK_MSG_ID_WAYPOINT_CURRENT_LEN = 2; @@ -1136,7 +1138,7 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_waypoint_reached_t { - public ushort seq; ///< Sequence + public ushort seq; /// Sequence }; public const byte MAVLINK_MSG_ID_WAYPOINT_REACHED_LEN = 2; @@ -1145,9 +1147,9 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_waypoint_request_t { - public byte target_system; ///< System ID - public byte target_component; ///< Component ID - public ushort seq; ///< Sequence + public byte target_system; /// System ID + public byte target_component; /// Component ID + public ushort seq; /// Sequence }; public const byte MAVLINK_MSG_ID_WAYPOINT_REQUEST_LEN = 4; @@ -1156,8 +1158,8 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_waypoint_request_list_t { - public byte target_system; ///< System ID - public byte target_component; ///< Component ID + public byte target_system; /// System ID + public byte target_component; /// Component ID }; public const byte MAVLINK_MSG_ID_WAYPOINT_REQUEST_LIST_LEN = 2; @@ -1166,9 +1168,9 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_waypoint_set_current_t { - public byte target_system; ///< System ID - public byte target_component; ///< Component ID - public ushort seq; ///< Sequence + public byte target_system; /// System ID + public byte target_component; /// Component ID + public ushort seq; /// Sequence }; public const byte MAVLINK_MSG_ID_WAYPOINT_SET_CURRENT_LEN = 4; @@ -1177,31 +1179,31 @@ namespace ArdupilotMega [StructLayout(LayoutKind.Sequential,Pack=1)] public struct __mavlink_waypoint_set_global_reference_t { - public byte target_system; ///< System ID - public byte target_component; ///< Component ID - public float global_x; ///< global x position - public float global_y; ///< global y position - public float global_z; ///< global z position - public float global_yaw; ///< global yaw orientation in radians, 0 = NORTH - public float local_x; ///< local x position that matches the global x position - public float local_y; ///< local y position that matches the global y position - public float local_z; ///< local z position that matches the global z position - public float local_yaw; ///< local yaw that matches the global yaw orientation + public byte target_system; /// System ID + public byte target_component; /// Component ID + public float global_x; /// global x position + public float global_y; /// global y position + public float global_z; /// global z position + public float global_yaw; /// global yaw orientation in radians, 0 = NORTH + public float local_x; /// local x position that matches the global x position + public float local_y; /// local y position that matches the global y position + public float local_z; /// local z position that matches the global z position + public float local_yaw; /// local yaw that matches the global yaw orientation }; public enum MAV_CLASS { - MAV_CLASS_GENERIC = 0, ///< Generic autopilot, full support for everything - MAV_CLASS_PIXHAWK = 1, ///< PIXHAWK autopilot, http://pixhawk.ethz.ch - MAV_CLASS_SLUGS = 2, ///< SLUGS autopilot, http://slugsuav.soe.ucsc.edu - MAV_CLASS_ARDUPILOTMEGA = 3, ///< ArduPilotMega / ArduCopter, http://diydrones.com - MAV_CLASS_OPENPILOT = 4, ///< OpenPilot, http://openpilot.org - MAV_CLASS_GENERIC_MISSION_WAYPOINTS_ONLY = 5, ///< Generic autopilot only supporting simple waypoints - MAV_CLASS_GENERIC_MISSION_NAVIGATION_ONLY = 6, ///< Generic autopilot supporting waypoints and other simple navigation commands - MAV_CLASS_GENERIC_MISSION_FULL = 7, ///< Generic autopilot supporting the full mission command set - MAV_CLASS_NONE = 8, ///< No valid autopilot - MAV_CLASS_NB ///< Number of autopilot classes + MAV_CLASS_GENERIC = 0, /// Generic autopilot, full support for everything + MAV_CLASS_PIXHAWK = 1, /// PIXHAWK autopilot, http://pixhawk.ethz.ch + MAV_CLASS_SLUGS = 2, /// SLUGS autopilot, http://slugsuav.soe.ucsc.edu + MAV_CLASS_ARDUPILOTMEGA = 3, /// ArduPilotMega / ArduCopter, http://diydrones.com + MAV_CLASS_OPENPILOT = 4, /// OpenPilot, http://openpilot.org + MAV_CLASS_GENERIC_MISSION_WAYPOINTS_ONLY = 5, /// Generic autopilot only supporting simple waypoints + MAV_CLASS_GENERIC_MISSION_NAVIGATION_ONLY = 6, /// Generic autopilot supporting waypoints and other simple navigation commands + MAV_CLASS_GENERIC_MISSION_FULL = 7, /// Generic autopilot supporting the full mission command set + MAV_CLASS_NONE = 8, /// No valid autopilot + MAV_CLASS_NB /// Number of autopilot classes }; public enum MAV_ACTION @@ -1249,21 +1251,21 @@ namespace ArdupilotMega MAV_ACTION_LOITER_MAX_TIME = 40, MAV_ACTION_START_HILSIM = 41, MAV_ACTION_STOP_HILSIM = 42, - MAV_ACTION_NB ///< Number of MAV actions + MAV_ACTION_NB /// Number of MAV actions }; public enum MAV_MODE { - MAV_MODE_UNINIT = 0, ///< System is in undefined state - MAV_MODE_LOCKED = 1, ///< Motors are blocked, system is safe - MAV_MODE_MANUAL = 2, ///< System is allowed to be active, under manual (RC) control - MAV_MODE_GUIDED = 3, ///< System is allowed to be active, under autonomous control, manual setpoint - MAV_MODE_AUTO = 4, ///< System is allowed to be active, under autonomous control and navigation - MAV_MODE_TEST1 = 5, ///< Generic test mode, for custom use - MAV_MODE_TEST2 = 6, ///< Generic test mode, for custom use - MAV_MODE_TEST3 = 7, ///< Generic test mode, for custom use - MAV_MODE_READY = 8, ///< System is ready, motors are unblocked, but controllers are inactive - MAV_MODE_RC_TRAINING = 9 ///< System is blocked, only RC valued are read and reported back + MAV_MODE_UNINIT = 0, /// System is in undefined state + MAV_MODE_LOCKED = 1, /// Motors are blocked, system is safe + MAV_MODE_MANUAL = 2, /// System is allowed to be active, under manual (RC) control + MAV_MODE_GUIDED = 3, /// System is allowed to be active, under autonomous control, manual setpoint + MAV_MODE_AUTO = 4, /// System is allowed to be active, under autonomous control and navigation + MAV_MODE_TEST1 = 5, /// Generic test mode, for custom use + MAV_MODE_TEST2 = 6, /// Generic test mode, for custom use + MAV_MODE_TEST3 = 7, /// Generic test mode, for custom use + MAV_MODE_READY = 8, /// System is ready, motors are unblocked, but controllers are inactive + MAV_MODE_RC_TRAINING = 9 /// System is blocked, only RC valued are read and reported back }; public enum MAV_STATE diff --git a/Tools/ArdupilotMegaPlanner/Properties/AssemblyInfo.cs b/Tools/ArdupilotMegaPlanner/Properties/AssemblyInfo.cs index a6ddb45003..a4ed2a9425 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.0.0.0")] -[assembly: AssemblyFileVersion("1.0.76")] +[assembly: AssemblyFileVersion("1.0.77")] [assembly: NeutralResourcesLanguageAttribute("")] diff --git a/Tools/ArdupilotMegaPlanner/Resources/MAVParam.txt b/Tools/ArdupilotMegaPlanner/Resources/MAVParam.txt index 011946774a..9a19416a3b 100644 --- a/Tools/ArdupilotMegaPlanner/Resources/MAVParam.txt +++ b/Tools/ArdupilotMegaPlanner/Resources/MAVParam.txt @@ -16,15 +16,15 @@ It includes both fixed wing (APM) and rotary wing (!ArduCopter) parameters. Some ||RLL2SRV_P||0||5||0.4||1||1||SERVO_ROLL_P - Attitude control gains - Tuning values for the attitude control PID loops. The P term is the primary tuning value. This determines how the control deflection varies in proportion to the required correction.|| ||RLL2SRV_I||0||1||0||1||1||SERVO_ROLL_I - Attitude control gains - Tuning values for the attitude control PID loops. The I term is used to help control surfaces settle. This value should normally be kept low.|| ||RLL2SRV_D||0||1||0||1||1||SERVO_ROLL_D - Attitude control gains - Tuning values for the attitude control PID loops. The D term is used to control overshoot. Avoid using or adjusting this term if you are not familiar with tuning PID loops. It should normally be zero for most aircraft.|| -||RLL2SRV_IMAX||0||3000||500||100||1||SERVO_ROLL_INT_MAX_CENTIDEGREE - In Degrees - Maximum control offset due to the integral. This prevents the control output from being overdriven due to a persistent offset (e.g. crosstracking). Default is 5 degrees.|| +||RLL2SRV_IMAX||0||3000||500||100||1||SERVO_ROLL_INT_MAX_DEGREE - In Degrees - Maximum control offset due to the integral. This prevents the control output from being overdriven due to a persistent offset (e.g. crosstracking). Default is 5 degrees.|| ||PTCH2SRV_P||0||5||0.6||1||1||SERVO_PITCH_P - Attitude control gains - Tuning values for the attitude control PID loops. The P term is the primary tuning value. This determines how the control deflection varies in proportion to the required correction.|| ||PTCH2SRV_I||0||1||0||1||1||SERVO_PITCH_I - Attitude control gains - Tuning values for the attitude control PID loops. The I term is used to help control surfaces settle. This value should normally be kept low.|| ||PTCH2SRV_D||0||1||0||1||1||SERVO_PITCH_D - Attitude control gains - Tuning values for the attitude control PID loops. The D term is used to control overshoot. Avoid using or adjusting this term if you are not familiar with tuning PID loops. It should normally be zero for most aircraft.|| -||PTCH2SRV_IMAX||0||3000||500||100||1||SERVO_PITCH_INT_MAX_CENTIDEGREE - In Degrees - Maximum control offset due to the integral. This prevents the control output from being overdriven due to a persistent offset (e.g. crosstracking). Default is 5 degrees.|| +||PTCH2SRV_IMAX||0||3000||500||100||1||SERVO_PITCH_INT_MAX_DEGREE - In Degrees - Maximum control offset due to the integral. This prevents the control output from being overdriven due to a persistent offset (e.g. crosstracking). Default is 5 degrees.|| ||ARSPD2PTCH_P||0||5||0.65||1||1||NAV_PITCH_ASP_P - P. I and D terms for pitch adjustments made to maintain airspeed.|| ||ARSPD2PTCH_I||0||1||0||1||1||NAV_PITCH_ASP_I - P. I and D terms for pitch adjustments made to maintain airspeed.|| ||ARSPD2PTCH_D||0||1||0||1||1||NAV_PITCH_ASP_D - P. I and D terms for pitch adjustments made to maintain airspeed.|| -||ARSPD2PTCH_IMA||0||3000||500||100||1||NAV_PITCH_ASP_INT_MAX_CMSEC - In Degrees - Maximum pitch offset due to the integral. This limits the control output from being overdriven due to a persistent offset (eg. inability to maintain the programmed airspeed).|| +||ARSPD2PTCH_IMA||0||3000||500||100||1||NAV_PITCH_ASP_INT_MAX - In Degrees - Maximum pitch offset due to the integral. This limits the control output from being overdriven due to a persistent offset (eg. inability to maintain the programmed airspeed).|| ||YW2SRV_P||0||5||0||1||1||SERVO_YAW_P - P. I and D terms for the YAW control. Note units of this control loop are unusual. PID input is in m/s**2|| ||YW2SRV_I||0||1||0||1||1||SERVO_YAW_I - P. I and D terms for the YAW control. Note units of this control loop are unusual. PID input is in m/s**2|| ||YW2SRV_D||0||1||0||1||1||SERVO_YAW_D - P. I and D terms for the YAW control. Note units of this control loop are unusual. PID input is in m/s**2|| @@ -36,7 +36,7 @@ It includes both fixed wing (APM) and rotary wing (!ArduCopter) parameters. Some ||ALT2PTCH_P||0||5||0.65||1||1||NAV_PITCH_ALT_P - P. I and D terms for pitch adjustments made to maintain altitude.|| ||ALT2PTCH_I||0||1||0||1||1||NAV_PITCH_ALT_I - P. I and D terms for pitch adjustments made to maintain altitude.|| ||ALT2PTCH_D||0||1||0||1||1||NAV_PITCH_ALT_D - P. I and D terms for pitch adjustments made to maintain altitude.|| -||ALT2PTCH_IMAX||0||3000||500||100||1||NAV_PITCH_ALT_INT_MAX_CM - In Meters - Maximum pitch offset due to the integral. This limits the control output from being overdriven due to a persistent offset (eg. inability to maintain the programmed altitude).|| +||ALT2PTCH_IMAX||0||3000||500||100||1||NAV_PITCH_ALT_INT_MAX - In Meters - Maximum pitch offset due to the integral. This limits the control output from being overdriven due to a persistent offset (eg. inability to maintain the programmed altitude).|| ||KFF_PTCHCOMP||-3||3||0.2||0.01||1||PITCH_COMP - In Percent - Adds pitch input to compensate for the loss of lift due to roll control.|| ||KFF_RDDRMIX||-3||3||0.5||0.01||1||RUDDER_MIX - Roll to yaw mixing. This allows for co-ordinated turns.|| ||KFF_PTCH2THR||-3||3||0||1||1||P_TO_T - Pitch to throttle feed-forward gain.|| @@ -107,13 +107,13 @@ It includes both fixed wing (APM) and rotary wing (!ArduCopter) parameters. Some ||AP_OFFSET|| || ||0|| || ||AP_OFFSET|| ||TRIM_PITCH_CD|| || ||0|| || ||TRIM_PITCH_CD|| ||ALT_HOLD_RTL||0||20000||10000||100||1||ALT_HOLD_HOME_CM - When the user performs a factory reset on the APM. Sets the flag for weather the current altitude or ALT_HOLD_HOME altitude should be used for Return To Launch. Also sets the value of USE_CURRENT_ALT in meters. This is mainly intended to allow users to start using the APM without programming a mission first.|| -||XTRK_ANGLE_CD||0||6000||3000||100||1||XTRACK_ENTRY_ANGLE_CENTIDEGREE - Maximum angle used to correct for track following.|| -||ROLL_SRV_MAX||0||100||4500||100||0||ROLL_SERVO_MAX_CENTIDEGREE|| -||PITCH_SRV_MAX||0||100||4500||100||0||PITCH_SERVO_MAX_CENTIDEGREE|| -||RUDER_SRV_MAX||0||100||4500||100||0||RUDDER_SERVO_MAX_CENTIDEGREE|| -||LIM_ROLL_CD||0||6000||4500||100||1||HEAD_MAX_CENTIDEGREE - The maximum commanded bank angle in either direction. The default is 45 degrees. Decrease this value if your aircraft is not stable or has difficulty maintaining altitude in a steep bank.|| -||LIM_PITCH_MAX||0||6000||1500||100||1||PITCH_MAX_CENTIDEGREE - The maximum commanded pitch up angle. The default is 15 degrees. Care should be taken not to set this value too large, as the aircraft may stall|| -||LIM_PITCH_MIN||-6000||0||-2500||100||1||PITCH_MIN_CENTIDEGREE - The maximum commanded pitch down angle. Note that this value must be negative. The default is -25 degrees. Care should be taken not to set this value too large as it may result in overspeeding the aircraft.|| +||XTRK_ANGLE_CD||0||6000||3000||100||1||XTRACK_ENTRY_ANGLE_DEGREE - Maximum angle used to correct for track following.|| +||ROLL_SRV_MAX||0||100||4500||100||0||ROLL_SERVO_MAX_DEGREE|| +||PITCH_SRV_MAX||0||100||4500||100||0||PITCH_SERVO_MAX_DEGREE|| +||RUDER_SRV_MAX||0||100||4500||100||0||RUDDER_SERVO_MAX_DEGREE|| +||LIM_ROLL_CD||0||6000||4500||100||1||HEAD_MAX_DEGREE - The maximum commanded bank angle in either direction. The default is 45 degrees. Decrease this value if your aircraft is not stable or has difficulty maintaining altitude in a steep bank.|| +||LIM_PITCH_MAX||0||6000||1500||100||1||PITCH_MAX_DEGREE - The maximum commanded pitch up angle. The default is 15 degrees. Care should be taken not to set this value too large, as the aircraft may stall|| +||LIM_PITCH_MIN||-6000||0||-2500||100||1||PITCH_MIN_DEGREE - The maximum commanded pitch down angle. Note that this value must be negative. The default is -25 degrees. Care should be taken not to set this value too large as it may result in overspeeding the aircraft.|| ||GND_ALT_CM||0||500000||0||100||1||GND_ALT_CM|| ||GND_ABS_PRESS|| || ||0|| || ||GND_ABS_PRESS|| ||COMPASS_DEC||-1.57075||1.57075||0||1|| ||COMPASS_DEC - Compass Declination|| diff --git a/Tools/ArdupilotMegaPlanner/bin/Release/Resources/MAVCmd.txt b/Tools/ArdupilotMegaPlanner/bin/Release/Resources/MAVCmd.txt new file mode 100644 index 0000000000..51caf769b8 --- /dev/null +++ b/Tools/ArdupilotMegaPlanner/bin/Release/Resources/MAVCmd.txt @@ -0,0 +1,19 @@ +WAYPOINT;WAYPOINT;Delay;Alt;Lat;Long +LOITER_UNLIM;LOITER_UNLIM;N/A;Alt;Lat;Long +LOITER_TURNS;LOITER_TURNS;Turns;Alt;Lat;Long +LOITER_TIME;LOITER_TIME;Time s*10;Alt;Lat;Long +RETURN_TO_LAUNCH;RETURN_TO_LAUNCH;N/A;Alt;Lat;Long +LAND;LAND;N/A;Alt;Lat;Long +TAKEOFF;TAKEOFF;Angle;Alt;N/A;N/A +CONDITION_DELAY;CONDITION_DELAY;N/A;N/A;Time (sec);N/A +CONDITION_CHANGE_ALT;CONDITION_CHANGE_ALT;N/A;Alt;Rate (cm/sec);N/A +CONDITION_DISTANCE;CONDITION_DISTANCE;N/A;N/A;Dist (m);N/A +CONDITION_YAW;CONDITION_YAW;Angle;Speed(deg/sec);Direction (1/-1);Relateiv(1)/Absolute(0) +DO_JUMP;DO_JUMP;WP #;N/A;Repeat Count;N/A +DO_CHANGE_SPEED;DO_CHANGE_SPEED;Type (0=as 1=gs);Speed (m/s);Throttle(%);N/A +DO_SET_HOME;DO_SET_HOME;Current(1)/Spec(0);Alt (m);Lat;Long +DO_SET_PARAMETER;DO_SET_PARAMETER;Param Number;Param Value;N/A;N/A +DO_REPEAT_RELAY;DO_REPEAT_RELAY;N/A;Repeat#;Delay (sec);N/A +DO_SET_RELAY;DO_SET_RELAY;Off(0)/On(1);N/A;N/A;N/A +DO_SET_SERVO;DO_SET_SERVO;Servo No;PWM;N/A;N/A +DO_REPEAT_SERVO;DO_REPEAT_SERVO;Servo No;PWM;Repeat#;Delay (sec) \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/bin/Release/Resources/MAVParam.txt b/Tools/ArdupilotMegaPlanner/bin/Release/Resources/MAVParam.txt new file mode 100644 index 0000000000..9a19416a3b --- /dev/null +++ b/Tools/ArdupilotMegaPlanner/bin/Release/Resources/MAVParam.txt @@ -0,0 +1,221 @@ +== MAVLink Parameters == (this is a copy fo the wiki page FYI) + +This is a list of all the user-modifiable MAVLink parameters and what they do. You can modify them via the MAVLink parameters window in any compatible GCS, such as the Mission Planner, HK GCS or !QGroundControl. + +It includes both fixed wing (APM) and rotary wing (!ArduCopter) parameters. Some may only be relevant for one platform or another. + +|| *EEPROM variable name* || *Min* || *Max* || *Default* || *Multiplier* || *Enabled (0 = no, 1 = yes)* || *Comment* || +||MAH|| || ||1|| || || || +||CURRENT_ENABLE|| || ||1|| || || || +||AOA|| || ||1|| || || || +||MAG_ENABLE|| || ||1|| || || || +||HDNG2RLL_P||0||5||0.7||1||1||NAV_ROLL_P - Navigation control gains. Tuning values for the navigation control PID loops. The P term is the primary tuning value. This determines how the control deflection varies in proportion to the required correction.|| +||HDNG2RLL_I||0||1||0.01||1||1||NAV_ROLL_I - Navigation control gains. Tuning values for the navigation control PID loops. The I term is used to control drift.|| +||HDNG2RLL_D||0||1||0.02||1||1||NAV_ROLL_D - Navigation control gains. Tuning values for the navigation control PID loops. The D term is used to control overshoot. Avoid adjusting this term if you are not familiar with tuning PID loops.|| +||HDNG2RLL_IMAX||0||3000||500||100||1||NAV_ROLL_INT_MAX_CENTIDEGREE - In Degrees - Maximum control offset due to the integral. This prevents the control output from being overdriven due to a persistent offset (e.g. native flight AoA). If you find this value is insufficient consider adjusting the AOA parameter.|| +||RLL2SRV_P||0||5||0.4||1||1||SERVO_ROLL_P - Attitude control gains - Tuning values for the attitude control PID loops. The P term is the primary tuning value. This determines how the control deflection varies in proportion to the required correction.|| +||RLL2SRV_I||0||1||0||1||1||SERVO_ROLL_I - Attitude control gains - Tuning values for the attitude control PID loops. The I term is used to help control surfaces settle. This value should normally be kept low.|| +||RLL2SRV_D||0||1||0||1||1||SERVO_ROLL_D - Attitude control gains - Tuning values for the attitude control PID loops. The D term is used to control overshoot. Avoid using or adjusting this term if you are not familiar with tuning PID loops. It should normally be zero for most aircraft.|| +||RLL2SRV_IMAX||0||3000||500||100||1||SERVO_ROLL_INT_MAX_DEGREE - In Degrees - Maximum control offset due to the integral. This prevents the control output from being overdriven due to a persistent offset (e.g. crosstracking). Default is 5 degrees.|| +||PTCH2SRV_P||0||5||0.6||1||1||SERVO_PITCH_P - Attitude control gains - Tuning values for the attitude control PID loops. The P term is the primary tuning value. This determines how the control deflection varies in proportion to the required correction.|| +||PTCH2SRV_I||0||1||0||1||1||SERVO_PITCH_I - Attitude control gains - Tuning values for the attitude control PID loops. The I term is used to help control surfaces settle. This value should normally be kept low.|| +||PTCH2SRV_D||0||1||0||1||1||SERVO_PITCH_D - Attitude control gains - Tuning values for the attitude control PID loops. The D term is used to control overshoot. Avoid using or adjusting this term if you are not familiar with tuning PID loops. It should normally be zero for most aircraft.|| +||PTCH2SRV_IMAX||0||3000||500||100||1||SERVO_PITCH_INT_MAX_DEGREE - In Degrees - Maximum control offset due to the integral. This prevents the control output from being overdriven due to a persistent offset (e.g. crosstracking). Default is 5 degrees.|| +||ARSPD2PTCH_P||0||5||0.65||1||1||NAV_PITCH_ASP_P - P. I and D terms for pitch adjustments made to maintain airspeed.|| +||ARSPD2PTCH_I||0||1||0||1||1||NAV_PITCH_ASP_I - P. I and D terms for pitch adjustments made to maintain airspeed.|| +||ARSPD2PTCH_D||0||1||0||1||1||NAV_PITCH_ASP_D - P. I and D terms for pitch adjustments made to maintain airspeed.|| +||ARSPD2PTCH_IMA||0||3000||500||100||1||NAV_PITCH_ASP_INT_MAX - In Degrees - Maximum pitch offset due to the integral. This limits the control output from being overdriven due to a persistent offset (eg. inability to maintain the programmed airspeed).|| +||YW2SRV_P||0||5||0||1||1||SERVO_YAW_P - P. I and D terms for the YAW control. Note units of this control loop are unusual. PID input is in m/s**2|| +||YW2SRV_I||0||1||0||1||1||SERVO_YAW_I - P. I and D terms for the YAW control. Note units of this control loop are unusual. PID input is in m/s**2|| +||YW2SRV_D||0||1||0||1||1||SERVO_YAW_D - P. I and D terms for the YAW control. Note units of this control loop are unusual. PID input is in m/s**2|| +||YW2SRV_IMAX||0||3000||0||100||1||SERVO_YAW_INT_MAX - Maximum control offset due to the integral. This prevents the control output from being overdriven due to a persistent offset (e.g. crosstracking).|| +||ENRGY2THR_P||0||5||0.5||1||1||THROTTLE_TE_P - P. I and D terms for throttle adjustments made to control altitude.|| +||ENRGY2THR_I||0||1||0||1||1||THROTTLE_TE_I - P. I and D terms for throttle adjustments made to control altitude.|| +||ENRGY2THR_D||0||1||0||1||1||THROTTLE_TE_D - P. I and D terms for throttle adjustments made to control altitude.|| +||ENRGY2THR_IMAX||0||100||20||1||1||THROTTLE_TE_INT_MAX - In Percent - Maximum throttle input due to the integral term. This limits the throttle from being overdriven due to a persistent offset (e.g. inability to maintain the programmed altitude).|| +||ALT2PTCH_P||0||5||0.65||1||1||NAV_PITCH_ALT_P - P. I and D terms for pitch adjustments made to maintain altitude.|| +||ALT2PTCH_I||0||1||0||1||1||NAV_PITCH_ALT_I - P. I and D terms for pitch adjustments made to maintain altitude.|| +||ALT2PTCH_D||0||1||0||1||1||NAV_PITCH_ALT_D - P. I and D terms for pitch adjustments made to maintain altitude.|| +||ALT2PTCH_IMAX||0||3000||500||100||1||NAV_PITCH_ALT_INT_MAX - In Meters - Maximum pitch offset due to the integral. This limits the control output from being overdriven due to a persistent offset (eg. inability to maintain the programmed altitude).|| +||KFF_PTCHCOMP||-3||3||0.2||0.01||1||PITCH_COMP - In Percent - Adds pitch input to compensate for the loss of lift due to roll control.|| +||KFF_RDDRMIX||-3||3||0.5||0.01||1||RUDDER_MIX - Roll to yaw mixing. This allows for co-ordinated turns.|| +||KFF_PTCH2THR||-3||3||0||1||1||P_TO_T - Pitch to throttle feed-forward gain.|| +||KFF_THR2PTCH||-3||3||0||1||1||T_TO_P - Throttle to pitch feed-forward gain.|| +||XTRK_GAIN_SC||0||100||100||100||1||XTRACK_GAIN_SCALED - Default value is 1.0 degrees per metre. Values lower than 0.001 will disable crosstrack compensation.|| +||ALT_MIX||0||1||1||0.01||1||ALTITUDE_MIX - In Percent - Configures the blend between GPS and pressure altitude. 0 = GPS altitude, 1 = Press alt, 0.5 = half and half, etc.|| +||ARSPD_RATIO||0||5||1.9936||1||1||AIRSPEED_RATIO - Adjust AIRSPEED_RATIO in small increments to calibrate the airspeed sensor relative to your GPS. The calculation and default value are optimized for speeds around 12 m/s|| +||WP_RADIUS||0||200||30||1||1||WP_RADIUS_DEFAULT - When the user performs a factory reset on the APM, sets the waypoint radius (the radius from a target waypoint within which the APM will consider itself to have arrived at the waypoint) to this value in meters. This is mainly intended to allow users to start using the APM without programming a mission first.|| +||WP_LOITER_RAD||0||200||60||1||1||LOITER_RADIUS_DEFAULT - When the user performs a factory reset on the APM, sets the loiter radius (the distance the APM will attempt to maintain from a waypoint while loitering) to this value in meters. This is mainly intended to allow users to start using the APM without programming a mission first.|| +||ARSPD_FBW_MIN||5||50||6||1||1||AIRSPEED_FBW_MIN - In m/s - Airspeed corresponding to minimum and maximum throttle in Fly By Wire B mode.|| +||ARSPD_FBW_MAX||5||50||22||1||1||AIRSPEED_FBW_MAX - In m/s - Airspeed corresponding to minimum and maximum throttle in Fly By Wire B mode. AIRSPEED_FBW_MAX also sets the maximum airspeed that the cruise airspeed can be ""nudged"" to in AUTO mode when ENABLE_STICK_MIXING is set. In AUTO the cruise airspeed can be increased between AIRSPEED_CRUISE and AIRSPEED_FBW_MAX by positioning the throttle stick in the top 1/2 of its range. Throttle stick in the bottom 1/2 provide regular AUTO control.|| +||THR_MIN||0||100||0||1||1||THROTTLE_MIN - The minimum throttle setting to which the autopilot will reduce the throttle while descending. The default is zero, which is suitable for aircraft with a steady power-off glide. Increase this value if your aircraft needs throttle to maintain a stable descent in level flight.|| +||THR_MAX||0||100||75||1||1||THROTTLE_MAX - The maximum throttle setting the autopilot will apply. The default is 75%. Reduce this value if your aicraft is overpowered or has complex flight characteristics at high throttle settings.|| +||THR_FAILSAFE||0||0||1|| || ||THROTTLE_FAILSAFE - The throttle failsafe allows you to configure a software failsafe activated by a setting on the throttle input channel (channel 3). This can be used to achieve a failsafe override on loss of radio control without having to sacrifice one of your FLIGHT_MODE settings as the throttle failsafe overrides the switch-selected mode. Throttle failsafe is enabled by setting THROTTLE_FAILSAFE to 1.|| +||THR_FS_ACTION||0||2||1||1|| ||THROTTLE_FAILSAFE_ACTION - The FAILSAFE_ACTION setting determines what APM will do when throttle failsafe mode is entered while flying in AUTO mode. This is important in order to avoid accidental failsafe behaviour when flying waypoints that take the aircraft temporarily out of radio range. If FAILSAFE_ACTION is 1 when failsafe is entered in AUTO or LOITER modes the aircraft will head for home in RTL mode. If the throttle channel moves back up it will return to AUTO or LOITER mode. The default behavior is to ignore throttle failsafe in AUTO and LOITER modes.|| +||TRIM_THROTTLE||0||90||45||1||1||THROTTLE_CRUISE - In Percent - The approximate throttle setting to achieve AIRSPEED_CRUISE in level flight. The default is 45% which is reasonable for a modestly powered aircraft.|| +||TRIM_AUTO||0||1||1||1||1||AUTO_TRIM - !ArduPilot Mega can update its trim settings by looking at the radio inputs when switching out of MANUAL mode. This allows you to manually trim your aircraft before switching to an assisted mode but it also means that you should avoid switching out of MANUAL while you have any control stick deflection.|| +||FLTMODE_CH||5||8||8||1||1||FLIGHT_MODE_CHANNEL - Flight modes assigned to the control channel, and the input channel that is read for the control mode. Use a servo tester or the !ArduPilotMega_demo test program to check your switch settings. ATTENTION: Some !ArduPilot Mega boards have radio channels marked 0-7 and others have them marked the standard 1-8. The FLIGHT_MODE_CHANNEL option uses channel numbers 1-8 (and defaults to 8). If you only have a three-position switch or just want three modes set your switch to produce 1165, 1425, and 1815 microseconds and configure FLIGHT_MODE 1 & 2, 3 & 4 and 5 & 6 to be the same. This is the default. If you have FLIGHT_MODE_CHANNEL set to 8 (the default) and your control channel connected to input channel 8, the hardware failsafe mode will activate for any control input over 1750ms.|| +||FLIGHT_MODE_1||0||14||11||1|| ||FLIGHT_MODE_1 - The following standard flight modes are available: MANUAL = Full manual control via the hardware multiplexer. STABILIZE = Tries to maintain level flight but can be overridden with radio control inputs. FLY_BY_WIRE_A = Autopilot style control via user input with manual throttle. FLY_BY_WIRE_B = Autopilot style control via user input, aispeed controlled with throttle. RTL = Returns to the Home location and then LOITERs at a safe altitude. AUTO = Autonomous flight based on programmed waypoints.|| +||FLIGHT_MODE_2||0||14||11||1|| ||FLIGHT_MODE_2|| +||FLIGHT_MODE_3||0||14||5||1|| ||FLIGHT_MODE_3|| +||FLIGHT_MODE_4||0||14||5||1|| ||FLIGHT_MODE_4|| +||FLIGHT_MODE_5||0||14||0||1|| ||FLIGHT_MODE_5|| +||FLIGHT_MODE_6||0||14||0||1|| ||FLIGHT_MODE_6|| +||RC1_MIN||900||2100||1500||1||1||PWM_RC1_MIN - Radio Settings - all radio settings represent the period of the pulse width modulated signal. Typically 1000 ms is the lower limit, 1500 is neutral, and 2000 is the upper limit|| +||RC1_MAX||900||2100||1500||1||1||PWM_RC1_MAX - Radio Settings - all radio settings represent the period of the pulse width modulated signal. Typically 1000 ms is the lower limit, 1500 is neutral, and 2000 is the upper limit|| +||RC1_TRIM||900||2100||1200||1||1||PWM_RC1_TRIM - Radio Settings - all radio settings represent the period of the pulse width modulated signal. Typically 1000 ms is the lower limit, 1500 is neutral, and 2000 is the upper limit|| +||RC2_MIN||900||2100||1500||1||1||PWM_RC2_MIN - Radio Settings - all radio settings represent the period of the pulse width modulated signal. Typically 1000 ms is the lower limit, 1500 is neutral, and 2000 is the upper limit|| +||RC2_MAX||900||2100||1500||1||1||PWM_RC2_MAX - Radio Settings - all radio settings represent the period of the pulse width modulated signal. Typically 1000 ms is the lower limit, 1500 is neutral, and 2000 is the upper limit|| +||RC2_TRIM||900||2100||1200||1||1||PWM_RC2_TRIM - Radio Settings - all radio settings represent the period of the pulse width modulated signal. Typically 1000 ms is the lower limit, 1500 is neutral, and 2000 is the upper limit|| +||RC3_MIN||900||2100||1500||1||1||PWM_RC3_MIN - Radio Settings - all radio settings represent the period of the pulse width modulated signal. Typically 1000 ms is the lower limit, 1500 is neutral, and 2000 is the upper limit|| +||RC3_MAX||900||2100||1500||1||1||PWM_RC3_MAX - Radio Settings - all radio settings represent the period of the pulse width modulated signal. Typically 1000 ms is the lower limit, 1500 is neutral, and 2000 is the upper limit || +||RC3_TRIM||900||2100||1500||1||1||PWM_RC3_TRIM - Radio Settings - all radio settings represent the period of the pulse width modulated signal. Typically 1000 ms is the lower limit, 1500 is neutral, and 2000 is the upper limit || +||RC4_MIN||900||2100||1500||1||1||PWM_RC4_MIN - Radio Settings - all radio settings represent the period of the pulse width modulated signal. Typically 1000 ms is the lower limit, 1500 is neutral, and 2000 is the upper limit || +||RC4_MAX||900||2100||1500||1||1||PWM_RC4_MAX - Radio Settings - all radio settings represent the period of the pulse width modulated signal. Typically 1000 ms is the lower limit, 1500 is neutral, and 2000 is the upper limit || +||RC4_TRIM||900||2100||1200||1||1||PWM_RC4_TRIM - Radio Settings - all radio settings represent the period of the pulse width modulated signal. Typically 1000 ms is the lower limit, 1500 is neutral, and 2000 is the upper limit || +||RC5_MIN||900||2100||1500||1||1||PWM_CH5_MIN - Radio Settings - all radio settings represent the period of the pulse width modulated signal. Typically 1000 ms is the lower limit, 1500 is neutral, and 2000 is the upper limit || +||RC5_MAX||900||2100||1500||1||1||PWM_CH5_MAX - Radio Settings - all radio settings represent the period of the pulse width modulated signal. Typically 1000 ms is the lower limit, 1500 is neutral, and 2000 is the upper limit || +||RC5_MAX||900||2100||1500||1||1||PWM_CH5_MAX - Radio Settings - all radio settings represent the period of the pulse width modulated signal. Typically 1000 ms is the lower limit, 1500 is neutral, and 2000 is the upper limit || +||RC5_TRIM||900||2100||1500||1||1||PWM_CH5_TRIM - Radio Settings - all radio settings represent the period of the pulse width modulated signal. Typically 1000 ms is the lower limit, 1500 is neutral, and 2000 is the upper limit || +||RC6_MIN||900||2100||1500||1||1||PWM_CH6_MIN - Radio Settings - all radio settings represent the period of the pulse width modulated signal. Typically 1000 ms is the lower limit, 1500 is neutral, and 2000 is the upper limit || +||RC6_MAX||900||2100||1500||1||1||PWM_CH6_MAX - Radio Settings - all radio settings represent the period of the pulse width modulated signal. Typically 1000 ms is the lower limit, 1500 is neutral, and 2000 is the upper limit || +||RC6_TRIM||900||2100||1500||1||1||PWM_CH6_TRIM - Radio Settings - all radio settings represent the period of the pulse width modulated signal. Typically 1000 ms is the lower limit, 1500 is neutral, and 2000 is the upper limit || +||RC7_MIN||900||2100||1500||1||1||PWM_CH7_MIN - Radio Settings - all radio settings represent the period of the pulse width modulated signal. Typically 1000 ms is the lower limit, 1500 is neutral, and 2000 is the upper limit || +||RC7_MAX||900||2100||1500||1||1||PWM_CH7_MAX - Radio Settings - all radio settings represent the period of the pulse width modulated signal. Typically 1000 ms is the lower limit, 1500 is neutral, and 2000 is the upper limit || +||RC7_TRIM||900||2100||1500||1||1||PWM_CH7_TRIM - Radio Settings - all radio settings represent the period of the pulse width modulated signal. Typically 1000 ms is the lower limit, 1500 is neutral, and 2000 is the upper limit || +||RC8_MIN||900||2100||1500||1||1||PWM_CH8_MIN - Radio Settings - all radio settings represent the period of the pulse width modulated signal. Typically 1000 ms is the lower limit, 1500 is neutral, and 2000 is the upper limit || +||RC8_MAX||900||2100||1500||1||1||PWM_CH8_MAX - Radio Settings - all radio settings represent the period of the pulse width modulated signal. Typically 1000 ms is the lower limit, 1500 is neutral, and 2000 is the upper limit || +||RC8_TRIM||900||2100||1500||1||1||PWM_CH8_TRIM - Radio Settings - all radio settings represent the period of the pulse width modulated signal. Typically 1000 ms is the lower limit, 1500 is neutral, and 2000 is the upper limit || +||IMU_OFFSET_0||0||0||0|| || ||IMU_OFFSET_0 - IMU Calibration|| +||IMU_OFFSET_1||0||0||0|| || ||IMU_OFFSET_1 - IMU Calibration|| +||IMU_OFFSET_2||0||0||0|| || ||IMU_OFFSET_2 - IMU Calibration|| +||IMU_OFFSET_3||0||0||0|| || ||IMU_OFFSET_3 - IMU Calibration|| +||IMU_OFFSET_4||0||0||0|| || ||IMU_OFFSET_4 - IMU Calibration|| +||IMU_OFFSET_5||0||0||0|| || ||IMU_OFFSET_5 - IMU Calibration|| +||YAW_MODE|| || ||0|| || ||YAW_MODE|| +||WP_MODE|| || ||0|| || ||WP_MODE|| +||WP_TOTAL||0||255|| ||0|| ||WP_TOTAL|| +||WP_INDEX||0||255|| ||0|| ||WP_INDEX|| +||CONFIG|| || ||1|| || ||CONFIG_OPTIONS|| +||SWITCH_ENABLE||0||1||1||1||1||REVERS_SWITCH_ENABLE - 0 = Off, 1 = On, Enables/Disables physical reverse switches on APM board|| +||FIRMWARE_VER|| || ||0|| || ||FIRMWARE_VER|| +||LOG_BITMASK||0||65535||334||1||1||LOG_BITMASK|| +||TRIM_ELEVON||900||2100||1500||1||1||TRIM_ELEVON|| +||THR_FS_VALUE||850||1000||950||1||1||THROTTLE_FS_VALUE - If the throttle failsafe is enabled, THROTTLE_FS_VALUE sets the channel value below which the failsafe engages. The default is 975ms, which is a very low throttle setting. Most transmitters will let you trim the manual throttle position up so that you cannot engage the failsafe with a regular stick movement. Configure your receiver's failsafe setting for the throttle channel to the absolute minimum, and use the !ArduPilotMega_demo program to check that you cannot reach that value with the throttle control. Leave a margin of at least 50 microseconds between the lowest throttle setting and THROTTLE_FS_VALUE.|| +||TRIM_ARSPD_CM||500||5000||1200||100||1||AIRSPEED_CRUISE_CM - The speed in metres per second to maintain during cruise. The default is 10m/s, which is a conservative value suitable for relatively small, light aircraft.|| +||GND_TEMP||-10||50||28||1||1||GND_TEMP - Ground Temperature|| +||AP_OFFSET|| || ||0|| || ||AP_OFFSET|| +||TRIM_PITCH_CD|| || ||0|| || ||TRIM_PITCH_CD|| +||ALT_HOLD_RTL||0||20000||10000||100||1||ALT_HOLD_HOME_CM - When the user performs a factory reset on the APM. Sets the flag for weather the current altitude or ALT_HOLD_HOME altitude should be used for Return To Launch. Also sets the value of USE_CURRENT_ALT in meters. This is mainly intended to allow users to start using the APM without programming a mission first.|| +||XTRK_ANGLE_CD||0||6000||3000||100||1||XTRACK_ENTRY_ANGLE_DEGREE - Maximum angle used to correct for track following.|| +||ROLL_SRV_MAX||0||100||4500||100||0||ROLL_SERVO_MAX_DEGREE|| +||PITCH_SRV_MAX||0||100||4500||100||0||PITCH_SERVO_MAX_DEGREE|| +||RUDER_SRV_MAX||0||100||4500||100||0||RUDDER_SERVO_MAX_DEGREE|| +||LIM_ROLL_CD||0||6000||4500||100||1||HEAD_MAX_DEGREE - The maximum commanded bank angle in either direction. The default is 45 degrees. Decrease this value if your aircraft is not stable or has difficulty maintaining altitude in a steep bank.|| +||LIM_PITCH_MAX||0||6000||1500||100||1||PITCH_MAX_DEGREE - The maximum commanded pitch up angle. The default is 15 degrees. Care should be taken not to set this value too large, as the aircraft may stall|| +||LIM_PITCH_MIN||-6000||0||-2500||100||1||PITCH_MIN_DEGREE - The maximum commanded pitch down angle. Note that this value must be negative. The default is -25 degrees. Care should be taken not to set this value too large as it may result in overspeeding the aircraft.|| +||GND_ALT_CM||0||500000||0||100||1||GND_ALT_CM|| +||GND_ABS_PRESS|| || ||0|| || ||GND_ABS_PRESS|| +||COMPASS_DEC||-1.57075||1.57075||0||1|| ||COMPASS_DEC - Compass Declination|| +||SR0_EXT_STAT||0||50||3||1||1||TELEMETRY_ENABLE Port 0 - Enable GPS_STATUS, CONTROL_STATUS, AUX_STATUS|| +||SR0_EXTRA1||0||50||10||1||1||TELEMETRY_ENABLE Port 0 - Enable MSG_ATTITUDE|| +||SR0_EXTRA2||0||50||3||1||1||TELEMETRY_ENABLE Port 0 - Enable MSG_VFR_HUD|| +||SR0_EXTRA3||0||50||3||1||1||TELEMETRY_ENABLE Port 0 - Not currently used|| +||SR0_POSITION||0||50||3||1||1||TELEMETRY_ENABLE Port 0 - Enable LOCAL_POSITION, GLOBAL_POSITION/GLOBAL_POSITION_INT messages|| +||SR0_RAW_CTRL||0||50||3||1||1||TELEMETRY_ENABLE Port 0 - Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, NAV_CONTROLLER_OUTPUT|| +||SR0_RAW_SENS||0||50||3||1||1||TELEMETRY_ENABLE Port 0 - Enable IMU_RAW, GPS_RAW, GPS_STATUS packets|| +||SR0_RC_CHAN||0||50||3||1||1||TELEMETRY_ENABLE Port 0 - Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW|| +||SR3_EXT_STAT||0||50||0||1||1||TELEMETRY_ENABLE Port 3 - Enable GPS_STATUS, CONTROL_STATUS, AUX_STATUS|| +||SR3_EXTRA1||0||50||0||1||1||TELEMETRY_ENABLE Port 3 - Enable MSG_ATTITUDE|| +||SR3_EXTRA2||0||50||0||1||1||TELEMETRY_ENABLE Port 3 - Enable MSG_VFR_HUD|| +||SR3_EXTRA3||0||50||0||1||1||TELEMETRY_ENABLE Port 3 - Not currently used|| +||SR3_POSITION||0||50||0||1||1||TELEMETRY_ENABLE Port 3 - Enable LOCAL_POSITION, GLOBAL_POSITION/GLOBAL_POSITION_INT messages|| +||SR3_RAW_CTRL||0||50||0||1||1||TELEMETRY_ENABLE Port 3 - Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, NAV_CONTROLLER_OUTPUT|| +||SR3_RAW_SENS||0||50||0||1||1||TELEMETRY_ENABLE Port 3 - Enable IMU_RAW, GPS_RAW, GPS_STATUS packets|| +||SR3_RC_CHAN||0||50||0||1||1||TELEMETRY_ENABLE Port 3 - Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW|| +||MAG_ENABLE||0||1||0||1||1||MAG_ENABLE - 0 = Off, 1 = On, Magnetometer Enable|| +||ARSPD_ENABLE||0||1||0||1||1||AIRSPEED_ENABLE - 0 = Off, 1 = On, Airspeed Sensor Enable|| +||BATT_CAPACITY||0||10000||1760||1||1||BATTERY_MAH - Battery capacity in mAh|| +||BATT_MONITOR||0||4||0||1||1||BATTERY_MONITOR - The value should be set to 0 to disable battery monitoring, 1 to measure cell voltages for a 3 cell lipo, 2 to measure cell voltages for a 4 cell lipo, 3 to measure the total battery voltage (only) on input 1, or 4 to measure total battery voltage on input 1 and current on input 2. || +||FS_GCS_ENABL||0||1||0||1||1||FS_GCS_ENABLE - 0 = Off, 1 = On, If the GCS heartbeat is lost for 20 seconds, the plane will Return to Launch|| +||FS_LONG_ACTN||0||1||0||1||1||FS_LONG_ACTION - 0 = Off, 1 = On, If heartbeat is lost for 20 srconds, the plane will Return to Launch|| +||FS_SHORT_ACTN||0||1||0||1||1||FS_SHORT_ACTION - 0 = Off, 1 = On, If heartbeat is lost for 1.5 seconds, the plane will circle until heartbeat is found again or 20 seconds has passed|| +||SYSID_MYGCS||0||255||255||1||1||SYSID_MYGCS - The system ID of the GCS|| +||SYSID_THISMAV||0||255||1||1||1||SYSID_THISMAV - The system ID of the MAVlink vehicle|| +||AOA|| || ||0|| || +||ACR_PIT_D|| || ||1|| || ||Description coming soon|| +||ACR_PIT_I|| || ||1|| || ||Description coming soon|| +||ACR_PIT_IMAX|| || ||1|| || ||Description coming soon|| +||ACR_PIT_P|| || ||1|| || ||Description coming soon|| +||ACR_RLL_D|| || ||1|| || ||Description coming soon|| +||ACR_RLL_I|| || ||1|| || ||Description coming soon|| +||ACR_RLL_IMAX|| || ||1|| || ||Description coming soon|| +||ACR_RLL_P|| || ||1|| || ||Description coming soon|| +||ACR_YAW_D|| || ||1|| || ||Description coming soon|| +||ACR_YAW_I|| || ||1|| || ||Description coming soon|| +||ACR_YAW_IMAX|| || ||1|| || ||Description coming soon|| +||ACR_YAW_P|| || ||1|| || ||Description coming soon|| +||ESC|| || ||1|| || ||ESC_CALIBRATE_MODE|| +||FRAME|| || ||1|| || ||FRAME_ORIENTATION || +||LOITER_RADIUS|| || ||1|| || ||Description coming soon|| +||NAV_LAT_D|| || ||1|| || ||Description coming soon|| +||NAV_LAT_I|| || ||1|| || ||Description coming soon|| +||NAV_LAT_IMAX|| || ||1|| || ||Description coming soon|| +||NAV_LAT_P|| || ||1|| || ||Description coming soon|| +||NAV_LON_D|| || ||1|| || ||Description coming soon|| +||NAV_LON_I|| || ||1|| || ||Description coming soon|| +||NAV_LON_IMAX|| || ||1|| || ||Description coming soon|| +||NAV_LON_P|| || ||1|| || ||Description coming soon|| +||NAV_WP_D|| || ||1|| || ||Description coming soon|| +||NAV_WP_I|| || ||1|| || ||Description coming soon|| +||NAV_WP_IMAX|| || ||1|| || ||Description coming soon|| +||NAV_WP_P|| || ||1|| || ||Description coming soon|| +||PITCH_MAX|| || ||1|| || ||Description coming soon|| +||SONAR_ENABLE||0||1||0||1||1||SONAR_ENABLE - 0 = Off, 1 = On, Sonar Enable|| +||STB_PIT_D|| || ||1|| || ||Description coming soon|| +||STB_PIT_I|| || ||1|| || ||Description coming soon|| +||STB_PIT_IMAX|| || ||1|| || ||Description coming soon|| +||STB_PIT_P|| || ||1|| || ||Description coming soon|| +||STB_RLL_D|| || ||1|| || ||Description coming soon|| +||STB_RLL_I|| || ||1|| || ||Description coming soon|| +||STB_RLL_IMAX|| || ||1|| || ||Description coming soon|| +||STB_RLL_P|| || ||1|| || ||Description coming soon|| +||STB_YAW_D|| || ||1|| || ||Description coming soon|| +||STB_YAW_I|| || ||1|| || ||Description coming soon|| +||STB_YAW_IMAX|| || ||1|| || ||Description coming soon|| +||STB_YAW_P|| || ||1|| || ||Description coming soon|| +||THR_BAR_D|| || ||1|| || ||Description coming soon|| +||THR_BAR_I|| || ||1|| || ||Description coming soon|| +||THR_BAR_IMAX|| || ||1|| || ||Description coming soon|| +||THR_BAR_P|| || ||1|| || ||Description coming soo|| +||THR_SON_D|| || ||1|| || ||Description coming soon|| +||THR_SON_I|| || ||1|| || ||Description coming soon|| +||THR_SON_IMAX|| || ||1|| || ||Description coming soon|| +||THR_SON_P|| || ||1|| || ||Description coming soon|| +||WP_MODE|| || ||1|| || ||Description coming soon|| +||WP_MUST_INDEX|| || ||1|| || ||Description coming soon|| +||XTRACK_ANGLE|| || ||1|| || ||Description coming soon|| +||XTRK_GAIN|| || ||1|| || ||Description coming soon|| +||ARSPD_OFFSET|| || ||0|| || ||Description coming soon|| +||ELEVON_CH1_REV||0||1||0||1||1||ELEVON_CHANNEL1_REVERSE - Channel Reversing (Future use on APM board 2.0) - Does not override dip switches|| +||ELEVON_CH2_REV||0||1||0||1||1||ELEVON_CHANNEL2_REVERSE - Channel Reversing (Future use on APM board 2.0) - Does not override dip switches|| +||ELEVON_MIXING||0||1||0||1||1||ELEVON_MIXING - 0 = Disabled, 1 = Enabled|| +||ELEVON_REVERSE||0||1||0||1||1||ELEVON_REVERSE - Channel Reversing (Future use on APM board 2.0) - Does not override dip switches|| +||INVERTEDFLT_CH||0||8||0||1||1||INVERTED_FLIGHT_CHANNEL - Channel to select inverted flight mode, 0 = Disabled|| +||RC1_REV||0||1||1||1||1||RC_CHANNEL1_REVERSE - Channel Reversing (Future use on APM board 2.0) - Does not override dip switches|| +||RC2_REV||0||1||1||1||1||RC_CHANNEL2_REVERSE - Channel Reversing (Future use on APM board 2.0) - Does not override dip switches|| +||RC3_REV||0||1||1||1||1||RC_CHANNEL3_REVERSE - Channel Reversing (Future use on APM board 2.0) - Does not override dip switches|| +||RC4_REV||0||1||1||1||1||RC_CHANNEL4_REVERSE - Channel Reversing (Future use on APM board 2.0) - Does not override dip switches|| +||RC5_REV||0||1||1||1||1||RC_CHANNEL5_REVERSE - Channel Reversing (Future use on APM board 2.0) - Does not override dip switches|| +||RC6_REV||0||1||1||1||1||RC_CHANNEL6_REVERSE - Channel Reversing (Future use on APM board 2.0) - Does not override dip switches|| +||RC7_REV||0||1||1||1||1||RC_CHANNEL7_REVERSE - Channel Reversing (Future use on APM board 2.0) - Does not override dip switches|| +||RC8_REV||0||1||1||1||1||RC_CHANNEL8_REVERSE - Channel Reversing (Future use on APM board 2.0) - Does not override dip switches|| +||SYSID_SW_MREV|| || ||0|| || ||Description coming soon|| +||SYSID_SW_TYPE|| || ||0|| || ||Description coming soon|| +||THR_SLEWRATE||0||100||0||1||1||THROTTLE_SLEW_RATE - 0 = Disabled, otherwise it limits throttle movement rate. Units are % per second. This is a test feature and may go away.|| +||FLTMODE1||0||20||1||1|| ||FLIGHT_MODE_1 - Mode switch setting 1 - APM: 0 = Manual, 2 = Stabilize, 5 - Fly-By-Wire-A, 6 = Fly-By-Wire-B, 7 = Fly-By-Wire-C, 10 = Auto - Mission, 11 = RTL, 12 = Loiter, 13 = Take-off, 14 = Land, 15= Guided; ACM2: 0 = Stabilize, 1 = Acro, 2 = Alt Hold, 3 = Auto, 4 = Guided, 5 = Loiter, 6 = RTL|| +||FLTMODE2||0||20||1||1|| ||FLIGHT_MODE_2 - Mode switch setting 2 - APM: 0 = Manual, 2 = Stabilize, 5 - Fly-By-Wire-A, 6 = Fly-By-Wire-B, 7 = Fly-By-Wire-C, 10 = Auto - Mission, 11 = RTL, 12 = Loiter, 13 = Take-off, 14 = Land, 15= Guided; ACM2: 0 = Stabilize, 1 = Acro, 2 = Alt Hold, 3 = Auto, 4 = Guided, 5 = Loiter, 6 = RTL|| +||FLTMODE3||0||20||1||1|| ||FLIGHT_MODE_3 - Mode switch setting 3 - APM: 0 = Manual, 2 = Stabilize, 5 - Fly-By-Wire-A, 6 = Fly-By-Wire-B, 7 = Fly-By-Wire-C, 10 = Auto - Mission, 11 = RTL, 12 = Loiter, 13 = Take-off, 14 = Land, 15= Guided; ACM2: 0 = Stabilize, 1 = Acro, 2 = Alt Hold, 3 = Auto, 4 = Guided, 5 = Loiter, 6 = RTL|| +||FLTMODE4||0||20||1||1|| ||FLIGHT_MODE_4 - Mode switch setting 4 - APM: 0 = Manual, 2 = Stabilize, 5 - Fly-By-Wire-A, 6 = Fly-By-Wire-B, 7 = Fly-By-Wire-C, 10 = Auto - Mission, 11 = RTL, 12 = Loiter, 13 = Take-off, 14 = Land, 15= Guided; ACM2: 0 = Stabilize, 1 = Acro, 2 = Alt Hold, 3 = Auto, 4 = Guided, 5 = Loiter, 6 = RTL|| +||FLTMODE5||0||20||1||1|| ||FLIGHT_MODE_5 - Mode switch setting 5 - APM: 0 = Manual, 2 = Stabilize, 5 - Fly-By-Wire-A, 6 = Fly-By-Wire-B, 7 = Fly-By-Wire-C, 10 = Auto - Mission, 11 = RTL, 12 = Loiter, 13 = Take-off, 14 = Land, 15= Guided; ACM2: 0 = Stabilize, 1 = Acro, 2 = Alt Hold, 3 = Auto, 4 = Guided, 5 = Loiter, 6 = RTL|| +||FLTMODE6||0||20||1||1|| ||FLIGHT_MODE_6 - Mode switch setting 6 - APM: 0 = Manual, 2 = Stabilize, 5 - Fly-By-Wire-A, 6 = Fly-By-Wire-B, 7 = Fly-By-Wire-C, 10 = Auto - Mission, 11 = RTL, 12 = Loiter, 13 = Take-off, 14 = Land, 15= Guided; ACM2: 0 = Stabilize, 1 = Acro, 2 = Alt Hold, 3 = Auto, 4 = Guided, 5 = Loiter, 6 = RTL|| \ No newline at end of file diff --git a/Tools/ArdupilotMegaPlanner/bin/Release/Resources/Welcome_to_Michael_Oborne.rtf b/Tools/ArdupilotMegaPlanner/bin/Release/Resources/Welcome_to_Michael_Oborne.rtf new file mode 100644 index 0000000000..c537652c1f Binary files /dev/null and b/Tools/ArdupilotMegaPlanner/bin/Release/Resources/Welcome_to_Michael_Oborne.rtf differ diff --git a/Tools/ArdupilotMegaPlanner/bin/Release/hud.html b/Tools/ArdupilotMegaPlanner/bin/Release/hud.html new file mode 100644 index 0000000000..ce9253d9e8 --- /dev/null +++ b/Tools/ArdupilotMegaPlanner/bin/Release/hud.html @@ -0,0 +1,225 @@ + + + + + + + +

This example requires a browser that supports the + HTML5 + <canvas> feature.

+
+ + diff --git a/Tools/ArdupilotMegaPlanner/hud.html b/Tools/ArdupilotMegaPlanner/hud.html new file mode 100644 index 0000000000..ce9253d9e8 --- /dev/null +++ b/Tools/ArdupilotMegaPlanner/hud.html @@ -0,0 +1,225 @@ + + + + + + + +

This example requires a browser that supports the + HTML5 + <canvas> feature.

+
+ + diff --git a/Tools/ArdupilotMegaPlanner/mavlinklist.pl b/Tools/ArdupilotMegaPlanner/mavlinklist.pl index 6686745a1e..43b0b6219e 100644 --- a/Tools/ArdupilotMegaPlanner/mavlinklist.pl +++ b/Tools/ArdupilotMegaPlanner/mavlinklist.pl @@ -75,6 +75,8 @@ foreach $file (@files) { $line =~ s/MAV_CMD_NAV_//; $line =~ s/MAV_CMD_//; + + $line =~ s/\/\/\/