mirror of https://github.com/ArduPilot/ardupilot
APM Planner 1.1.63
update radio packet fix rlogs add left/right mavlink log graphing (left/right mouse) modify update detector.
This commit is contained in:
parent
7921d33c40
commit
451314aa16
|
@ -148,11 +148,11 @@
|
|||
</Reference>
|
||||
<Reference Include="Microsoft.DirectX, Version=1.0.2902.0, Culture=neutral, PublicKeyToken=31bf3856ad364e35">
|
||||
<SpecificVersion>False</SpecificVersion>
|
||||
<Private>False</Private>
|
||||
<Private>True</Private>
|
||||
</Reference>
|
||||
<Reference Include="Microsoft.DirectX.DirectInput, Version=1.0.2902.0, Culture=neutral, PublicKeyToken=31bf3856ad364e35">
|
||||
<SpecificVersion>False</SpecificVersion>
|
||||
<Private>False</Private>
|
||||
<Private>True</Private>
|
||||
</Reference>
|
||||
<Reference Include="Microsoft.Dynamic">
|
||||
</Reference>
|
||||
|
@ -1147,8 +1147,7 @@
|
|||
<ItemGroup />
|
||||
<Import Project="$(MSBuildToolsPath)\Microsoft.CSharp.targets" />
|
||||
<PropertyGroup>
|
||||
<PostBuildEvent>
|
||||
</PostBuildEvent>
|
||||
<PostBuildEvent>"$(TargetDir)version.exe" "$(TargetPath)" > "$(TargetDir)version.txt"</PostBuildEvent>
|
||||
</PropertyGroup>
|
||||
<PropertyGroup>
|
||||
<PreBuildEvent>
|
||||
|
|
|
@ -16,9 +16,9 @@ namespace ArdupilotMega
|
|||
{
|
||||
static class CodeGen
|
||||
{
|
||||
public static string runCode(string code)
|
||||
public static object runCode(string code)
|
||||
{
|
||||
string answer = "";
|
||||
object answer = null;
|
||||
|
||||
GetMathMemberNames();
|
||||
|
||||
|
@ -305,7 +305,7 @@ namespace ArdupilotMega
|
|||
classDeclaration.IsClass = true;
|
||||
classDeclaration.Name = "Calculator";
|
||||
classDeclaration.Attributes = MemberAttributes.Public;
|
||||
classDeclaration.Members.Add(FieldVariable("answer", typeof(string), MemberAttributes.Private));
|
||||
classDeclaration.Members.Add(FieldVariable("answer", typeof(object), MemberAttributes.Private));
|
||||
|
||||
//default constructor
|
||||
CodeConstructor defaultConstructor = new CodeConstructor();
|
||||
|
@ -315,16 +315,16 @@ namespace ArdupilotMega
|
|||
classDeclaration.Members.Add(defaultConstructor);
|
||||
|
||||
//property
|
||||
classDeclaration.Members.Add(MakeProperty("Answer", "answer", typeof(string)));
|
||||
classDeclaration.Members.Add(MakeProperty("Answer", "answer", typeof(object)));
|
||||
|
||||
//Our Calculate Method
|
||||
CodeMemberMethod myMethod = new CodeMemberMethod();
|
||||
myMethod.Name = "Calculate";
|
||||
myMethod.ReturnType = new CodeTypeReference(typeof(string));
|
||||
myMethod.ReturnType = new CodeTypeReference(typeof(object));
|
||||
myMethod.Comments.Add(new CodeCommentStatement("Calculate an expression", true));
|
||||
myMethod.Attributes = MemberAttributes.Public;
|
||||
myMethod.Statements.Add(new CodeAssignStatement(new CodeSnippetExpression("Object obj"), new CodeSnippetExpression(expression)));
|
||||
myMethod.Statements.Add(new CodeAssignStatement(new CodeSnippetExpression("Answer"), new CodeSnippetExpression("obj.ToString()")));
|
||||
//myMethod.Statements.Add(new CodeAssignStatement(new CodeSnippetExpression("Answer"), new CodeSnippetExpression("obj.ToString()")));
|
||||
myMethod.Statements.Add(
|
||||
new CodeMethodReturnStatement(new CodeFieldReferenceExpression(new CodeThisReferenceExpression(), "Answer")));
|
||||
classDeclaration.Members.Add(myMethod);
|
||||
|
|
|
@ -121,11 +121,6 @@ namespace System.Windows.Forms
|
|||
return answer;
|
||||
}
|
||||
|
||||
static void msgBoxFrm_FormClosing(object sender, FormClosingEventArgs e)
|
||||
{
|
||||
throw new NotImplementedException();
|
||||
}
|
||||
|
||||
// from http://stackoverflow.com/questions/2512781/winforms-big-paragraph-tooltip/2512895#2512895
|
||||
private static int maximumSingleLineTooltipLength = 85;
|
||||
|
||||
|
|
|
@ -256,8 +256,9 @@ namespace ArdupilotMega
|
|||
public float rssi { get; set; }
|
||||
public float remrssi { get; set; }
|
||||
public byte txbuffer { get; set; }
|
||||
public float noise { get; set; }
|
||||
public float remnoise { get; set; }
|
||||
public ushort rxerrors { get; set; }
|
||||
public ushort serrors { get; set; }
|
||||
public ushort fixedp { get; set; }
|
||||
|
||||
// stats
|
||||
|
@ -703,7 +704,8 @@ namespace ArdupilotMega
|
|||
remrssi = radio.remrssi;
|
||||
txbuffer = radio.txbuf;
|
||||
rxerrors = radio.rxerrors;
|
||||
serrors = radio.serrors;
|
||||
noise = radio.noise;
|
||||
remnoise = radio.remnoise;
|
||||
fixedp = radio.fixedp;
|
||||
}
|
||||
|
||||
|
|
|
@ -910,16 +910,16 @@
|
|||
<value>NoControl</value>
|
||||
</data>
|
||||
<data name="BUT_log2kml.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>51, 32</value>
|
||||
<value>29, 32</value>
|
||||
</data>
|
||||
<data name="BUT_log2kml.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>80, 23</value>
|
||||
<value>127, 23</value>
|
||||
</data>
|
||||
<data name="BUT_log2kml.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>76</value>
|
||||
</data>
|
||||
<data name="BUT_log2kml.Text" xml:space="preserve">
|
||||
<value>Log > KML</value>
|
||||
<value>Tlog > Kml or Graph</value>
|
||||
</data>
|
||||
<data name=">>BUT_log2kml.Name" xml:space="preserve">
|
||||
<value>BUT_log2kml</value>
|
||||
|
|
|
@ -2094,7 +2094,8 @@ namespace ArdupilotMega
|
|||
int read = BaseStream.Read(temp, 6, length - 4);
|
||||
if (rawlogfile != null && rawlogfile.BaseStream.CanWrite)
|
||||
{
|
||||
rawlogfile.Write(temp, 0, read);
|
||||
// write only what we read, temp is the whole packet, so 6-end
|
||||
rawlogfile.Write(temp, 6, read);
|
||||
rawlogfile.BaseStream.Flush();
|
||||
}
|
||||
}
|
||||
|
@ -2258,6 +2259,7 @@ namespace ArdupilotMega
|
|||
Array.Reverse(datearray);
|
||||
logfile.Write(datearray, 0, datearray.Length);
|
||||
logfile.Write(temp, 0, temp.Length);
|
||||
logfile.Flush();
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -5,10 +5,10 @@ using System.Runtime.InteropServices;
|
|||
|
||||
namespace ArdupilotMega
|
||||
{
|
||||
#if MAVLINK10
|
||||
#if MAVLINK10
|
||||
partial class MAVLink
|
||||
{
|
||||
public const string MAVLINK_BUILD_DATE = "Fri Apr 6 21:11:00 2012";
|
||||
public const string MAVLINK_BUILD_DATE = "Sun Apr 8 12:29:46 2012";
|
||||
public const string MAVLINK_WIRE_PROTOCOL_VERSION = "1.0";
|
||||
public const int MAVLINK_MAX_DIALECT_PAYLOAD_SIZE = 42;
|
||||
|
||||
|
@ -27,7 +27,7 @@ namespace ArdupilotMega
|
|||
|
||||
public byte[] MAVLINK_MESSAGE_LENGTHS = new byte[] {9, 31, 12, 0, 14, 28, 3, 32, 0, 0, 0, 6, 0, 0, 0, 0, 0, 0, 0, 0, 20, 2, 25, 23, 30, 101, 22, 26, 16, 14, 28, 32, 28, 28, 22, 22, 21, 6, 6, 37, 4, 4, 2, 2, 4, 2, 2, 3, 13, 12, 19, 17, 15, 15, 27, 25, 18, 18, 20, 20, 0, 0, 26, 0, 36, 0, 6, 4, 0, 21, 18, 0, 0, 0, 20, 0, 33, 3, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 56, 42, 33, 0, 0, 0, 0, 0, 0, 0, 18, 32, 32, 20, 32, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 42, 8, 4, 12, 15, 13, 6, 15, 14, 0, 12, 3, 8, 28, 36, 3, 9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 30, 18, 18, 51, 9, 3};
|
||||
|
||||
public byte[] MAVLINK_MESSAGE_CRCS = new byte[] {50, 124, 137, 0, 237, 217, 104, 119, 0, 0, 0, 89, 0, 0, 0, 0, 0, 0, 0, 0, 214, 159, 220, 168, 24, 23, 170, 144, 67, 115, 39, 246, 185, 104, 237, 244, 222, 212, 9, 254, 230, 28, 28, 132, 221, 232, 11, 153, 41, 39, 214, 223, 141, 33, 15, 3, 100, 24, 239, 238, 0, 0, 183, 0, 130, 0, 148, 21, 0, 52, 124, 0, 0, 0, 20, 0, 152, 143, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 183, 63, 54, 0, 0, 0, 0, 0, 0, 0, 19, 102, 158, 208, 56, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 134, 219, 208, 188, 84, 22, 19, 21, 134, 0, 78, 68, 189, 127, 42, 21, 244, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 204, 49, 170, 44, 83, 46, 247};
|
||||
public byte[] MAVLINK_MESSAGE_CRCS = new byte[] {50, 124, 137, 0, 237, 217, 104, 119, 0, 0, 0, 89, 0, 0, 0, 0, 0, 0, 0, 0, 214, 159, 220, 168, 24, 23, 170, 144, 67, 115, 39, 246, 185, 104, 237, 244, 222, 212, 9, 254, 230, 28, 28, 132, 221, 232, 11, 153, 41, 39, 214, 223, 141, 33, 15, 3, 100, 24, 239, 238, 0, 0, 183, 0, 130, 0, 148, 21, 0, 52, 124, 0, 0, 0, 20, 0, 152, 143, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 183, 63, 54, 0, 0, 0, 0, 0, 0, 0, 19, 102, 158, 208, 56, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 134, 219, 208, 188, 84, 22, 19, 21, 134, 0, 78, 68, 189, 127, 42, 21, 21, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 204, 49, 170, 44, 83, 46, 247};
|
||||
|
||||
public Type[] MAVLINK_MESSAGE_INFO = new Type[] {typeof( mavlink_heartbeat_t ), typeof( mavlink_sys_status_t ), typeof( mavlink_system_time_t ), null, typeof( mavlink_ping_t ), typeof( mavlink_change_operator_control_t ), typeof( mavlink_change_operator_control_ack_t ), typeof( mavlink_auth_key_t ), null, null, null, typeof( mavlink_set_mode_t ), null, null, null, null, null, null, null, null, typeof( mavlink_param_request_read_t ), typeof( mavlink_param_request_list_t ), typeof( mavlink_param_value_t ), typeof( mavlink_param_set_t ), typeof( mavlink_gps_raw_int_t ), typeof( mavlink_gps_status_t ), typeof( mavlink_scaled_imu_t ), typeof( mavlink_raw_imu_t ), typeof( mavlink_raw_pressure_t ), typeof( mavlink_scaled_pressure_t ), typeof( mavlink_attitude_t ), typeof( mavlink_attitude_quaternion_t ), typeof( mavlink_local_position_ned_t ), typeof( mavlink_global_position_int_t ), typeof( mavlink_rc_channels_scaled_t ), typeof( mavlink_rc_channels_raw_t ), typeof( mavlink_servo_output_raw_t ), typeof( mavlink_mission_request_partial_list_t ), typeof( mavlink_mission_write_partial_list_t ), typeof( mavlink_mission_item_t ), typeof( mavlink_mission_request_t ), typeof( mavlink_mission_set_current_t ), typeof( mavlink_mission_current_t ), typeof( mavlink_mission_request_list_t ), typeof( mavlink_mission_count_t ), typeof( mavlink_mission_clear_all_t ), typeof( mavlink_mission_item_reached_t ), typeof( mavlink_mission_ack_t ), typeof( mavlink_set_gps_global_origin_t ), typeof( mavlink_gps_global_origin_t ), typeof( mavlink_set_local_position_setpoint_t ), typeof( mavlink_local_position_setpoint_t ), typeof( mavlink_global_position_setpoint_int_t ), typeof( mavlink_set_global_position_setpoint_int_t ), typeof( mavlink_safety_set_allowed_area_t ), typeof( mavlink_safety_allowed_area_t ), typeof( mavlink_set_roll_pitch_yaw_thrust_t ), typeof( mavlink_set_roll_pitch_yaw_speed_thrust_t ), typeof( mavlink_roll_pitch_yaw_thrust_setpoint_t ), typeof( mavlink_roll_pitch_yaw_speed_thrust_setpoint_t ), null, null, typeof( mavlink_nav_controller_output_t ), null, typeof( mavlink_state_correction_t ), null, typeof( mavlink_request_data_stream_t ), typeof( mavlink_data_stream_t ), null, typeof( mavlink_manual_control_t ), typeof( mavlink_rc_channels_override_t ), null, null, null, typeof( mavlink_vfr_hud_t ), null, typeof( mavlink_command_long_t ), typeof( mavlink_command_ack_t ), null, null, null, null, null, null, null, null, null, null, null, null, typeof( mavlink_hil_state_t ), typeof( mavlink_hil_controls_t ), typeof( mavlink_hil_rc_inputs_raw_t ), null, null, null, null, null, null, null, typeof( mavlink_optical_flow_t ), typeof( mavlink_global_vision_position_estimate_t ), typeof( mavlink_vision_position_estimate_t ), typeof( mavlink_vision_speed_estimate_t ), typeof( mavlink_vicon_position_estimate_t ), null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, typeof( mavlink_sensor_offsets_t ), typeof( mavlink_set_mag_offsets_t ), typeof( mavlink_meminfo_t ), typeof( mavlink_ap_adc_t ), typeof( mavlink_digicam_configure_t ), typeof( mavlink_digicam_control_t ), typeof( mavlink_mount_configure_t ), typeof( mavlink_mount_control_t ), typeof( mavlink_mount_status_t ), null, typeof( mavlink_fence_point_t ), typeof( mavlink_fence_fetch_point_t ), typeof( mavlink_fence_status_t ), typeof( mavlink_ahrs_t ), typeof( mavlink_simstate_t ), typeof( mavlink_hwstatus_t ), typeof( mavlink_radio_t ), null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, typeof( mavlink_memory_vect_t ), typeof( mavlink_debug_vect_t ), typeof( mavlink_named_value_float_t ), typeof( mavlink_named_value_int_t ), typeof( mavlink_statustext_t ), typeof( mavlink_debug_t ), typeof( mavlink_extended_message_t )};
|
||||
|
||||
|
@ -56,25 +56,25 @@ namespace ArdupilotMega
|
|||
public enum MAV_CMD
|
||||
{
|
||||
///<summary> Navigate to MISSION. |Hold time in decimal seconds. (ignored by fixed wing, time to stay at MISSION for rotary wing)| Acceptance radius in meters (if the sphere with this radius is hit, the MISSION counts as reached)| 0 to pass through the WP, if > 0 radius in meters to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control.| Desired yaw angle at MISSION (rotary wing)| Latitude| Longitude| Altitude| </summary>
|
||||
WAYPOINT=16,
|
||||
NAV_WAYPOINT=16,
|
||||
///<summary> Loiter around this MISSION an unlimited amount of time |Empty| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| </summary>
|
||||
LOITER_UNLIM=17,
|
||||
NAV_LOITER_UNLIM=17,
|
||||
///<summary> Loiter around this MISSION for X turns |Turns| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| </summary>
|
||||
LOITER_TURNS=18,
|
||||
NAV_LOITER_TURNS=18,
|
||||
///<summary> Loiter around this MISSION for X seconds |Seconds (decimal)| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| </summary>
|
||||
LOITER_TIME=19,
|
||||
NAV_LOITER_TIME=19,
|
||||
///<summary> Return to launch location |Empty| Empty| Empty| Empty| Empty| Empty| Empty| </summary>
|
||||
RETURN_TO_LAUNCH=20,
|
||||
NAV_RETURN_TO_LAUNCH=20,
|
||||
///<summary> Land at location |Empty| Empty| Empty| Desired yaw angle.| Latitude| Longitude| Altitude| </summary>
|
||||
LAND=21,
|
||||
NAV_LAND=21,
|
||||
///<summary> Takeoff from ground / hand |Minimum pitch (if airspeed sensor present), desired pitch without sensor| Empty| Empty| Yaw angle (if magnetometer present), ignored without magnetometer| Latitude| Longitude| Altitude| </summary>
|
||||
TAKEOFF=22,
|
||||
NAV_TAKEOFF=22,
|
||||
///<summary> Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Region of intereset mode. (see MAV_ROI enum)| MISSION index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple ROI's)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z| </summary>
|
||||
ROI=80,
|
||||
NAV_ROI=80,
|
||||
///<summary> Control autonomous path planning on the MAV. |0: Disable local obstacle avoidance / local path planning (without resetting map), 1: Enable local path planning, 2: Enable and reset local path planning| 0: Disable full path planning (without resetting map), 1: Enable, 2: Enable and reset map/occupancy grid, 3: Enable and reset planned route, but not occupancy grid| Empty| Yaw angle at goal, in compass degrees, [0..360]| Latitude/X of goal| Longitude/Y of goal| Altitude/Z of goal| </summary>
|
||||
PATHPLANNING=81,
|
||||
NAV_PATHPLANNING=81,
|
||||
///<summary> NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| </summary>
|
||||
LAST=95,
|
||||
NAV_LAST=95,
|
||||
///<summary> Delay mission state machine. |Delay in seconds (decimal)| Empty| Empty| Empty| Empty| Empty| Empty| </summary>
|
||||
CONDITION_DELAY=112,
|
||||
///<summary> Ascend/descend at rate. Delay mission state machine until desired altitude reached. |Descent / Ascend rate (m/s)| Empty| Empty| Empty| Empty| Empty| Finish Altitude| </summary>
|
||||
|
@ -915,16 +915,18 @@ namespace ArdupilotMega
|
|||
{
|
||||
/// <summary> receive errors </summary>
|
||||
public UInt16 rxerrors;
|
||||
/// <summary> serial errors </summary>
|
||||
public UInt16 serrors;
|
||||
/// <summary> count of error corrected packets </summary>
|
||||
public UInt16 fixedp;
|
||||
public UInt16 fixed;
|
||||
/// <summary> local signal strength </summary>
|
||||
public byte rssi;
|
||||
/// <summary> remote signal strength </summary>
|
||||
public byte remrssi;
|
||||
/// <summary> how full the tx buffer is as a percentage </summary>
|
||||
public byte txbuf;
|
||||
/// <summary> background noise level </summary>
|
||||
public byte noise;
|
||||
/// <summary> remote background noise level </summary>
|
||||
public byte remnoise;
|
||||
|
||||
};
|
||||
|
||||
|
@ -1108,7 +1110,7 @@ namespace ArdupilotMega
|
|||
public UInt16 param_index;
|
||||
/// <summary> Onboard parameter id </summary>
|
||||
[MarshalAs(UnmanagedType.ByValArray,SizeConst=16)]
|
||||
public byte[] param_id;
|
||||
public string param_id;
|
||||
/// <summary> Onboard parameter type: see MAV_VAR enum </summary>
|
||||
public byte param_type;
|
||||
|
||||
|
@ -1127,7 +1129,7 @@ namespace ArdupilotMega
|
|||
public byte target_component;
|
||||
/// <summary> Onboard parameter id </summary>
|
||||
[MarshalAs(UnmanagedType.ByValArray,SizeConst=16)]
|
||||
public byte[] param_id;
|
||||
public string param_id;
|
||||
/// <summary> Onboard parameter type: see MAV_VAR enum </summary>
|
||||
public byte param_type;
|
||||
|
||||
|
@ -2370,5 +2372,5 @@ namespace ArdupilotMega
|
|||
};
|
||||
|
||||
}
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
|
|
|
@ -5,10 +5,10 @@ using System.Runtime.InteropServices;
|
|||
|
||||
namespace ArdupilotMega
|
||||
{
|
||||
#if !MAVLINK10
|
||||
#if !MAVLINK10
|
||||
partial class MAVLink
|
||||
{
|
||||
public const string MAVLINK_BUILD_DATE = "Fri Apr 6 21:10:55 2012";
|
||||
public const string MAVLINK_BUILD_DATE = "Sun Apr 8 12:29:41 2012";
|
||||
public const string MAVLINK_WIRE_PROTOCOL_VERSION = "0.9";
|
||||
public const int MAVLINK_MAX_DIALECT_PAYLOAD_SIZE = 42;
|
||||
|
||||
|
@ -27,7 +27,7 @@ namespace ArdupilotMega
|
|||
|
||||
public byte[] MAVLINK_MESSAGE_LENGTHS = new byte[] {3, 4, 8, 14, 8, 28, 3, 32, 0, 2, 3, 2, 2, 0, 0, 0, 0, 0, 0, 0, 19, 2, 23, 21, 0, 37, 26, 101, 26, 16, 32, 32, 37, 32, 11, 17, 17, 16, 18, 36, 4, 4, 2, 2, 4, 2, 2, 3, 14, 12, 18, 16, 8, 27, 25, 18, 18, 24, 24, 0, 0, 0, 26, 16, 36, 5, 6, 56, 26, 21, 18, 0, 0, 18, 20, 20, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 18, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 0, 0, 0, 0, 0, 0, 0, 0, 0, 42, 8, 4, 12, 15, 13, 6, 15, 14, 0, 12, 3, 8, 28, 36, 3, 9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 30, 14, 14, 51, 5};
|
||||
|
||||
public byte[] MAVLINK_MESSAGE_CRCS = new byte[] {72, 39, 190, 92, 191, 217, 104, 119, 0, 219, 60, 186, 10, 0, 0, 0, 0, 0, 0, 0, 89, 159, 162, 121, 0, 149, 222, 110, 179, 136, 66, 126, 185, 147, 112, 252, 162, 215, 229, 128, 9, 106, 101, 213, 4, 229, 21, 214, 215, 14, 206, 50, 157, 126, 108, 213, 95, 5, 127, 0, 0, 0, 57, 126, 130, 119, 193, 191, 236, 158, 143, 0, 0, 104, 123, 131, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 174, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 155, 0, 0, 0, 0, 0, 0, 0, 0, 0, 143, 29, 208, 188, 118, 242, 19, 97, 233, 0, 18, 68, 136, 127, 42, 21, 143, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 178, 224, 60, 106, 7};
|
||||
public byte[] MAVLINK_MESSAGE_CRCS = new byte[] {72, 39, 190, 92, 191, 217, 104, 119, 0, 219, 60, 186, 10, 0, 0, 0, 0, 0, 0, 0, 89, 159, 162, 121, 0, 149, 222, 110, 179, 136, 66, 126, 185, 147, 112, 252, 162, 215, 229, 128, 9, 106, 101, 213, 4, 229, 21, 214, 215, 14, 206, 50, 157, 126, 108, 213, 95, 5, 127, 0, 0, 0, 57, 126, 130, 119, 193, 191, 236, 158, 143, 0, 0, 104, 123, 131, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 174, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 155, 0, 0, 0, 0, 0, 0, 0, 0, 0, 143, 29, 208, 188, 118, 242, 19, 97, 233, 0, 18, 68, 136, 127, 42, 21, 93, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 178, 224, 60, 106, 7};
|
||||
|
||||
public Type[] MAVLINK_MESSAGE_INFO = new Type[] {typeof( mavlink_heartbeat_t ), typeof( mavlink_boot_t ), typeof( mavlink_system_time_t ), typeof( mavlink_ping_t ), typeof( mavlink_system_time_utc_t ), typeof( mavlink_change_operator_control_t ), typeof( mavlink_change_operator_control_ack_t ), typeof( mavlink_auth_key_t ), null, typeof( mavlink_action_ack_t ), typeof( mavlink_action_t ), typeof( mavlink_set_mode_t ), typeof( mavlink_set_nav_mode_t ), null, null, null, null, null, null, null, typeof( mavlink_param_request_read_t ), typeof( mavlink_param_request_list_t ), typeof( mavlink_param_value_t ), typeof( mavlink_param_set_t ), null, typeof( mavlink_gps_raw_int_t ), typeof( mavlink_scaled_imu_t ), typeof( mavlink_gps_status_t ), typeof( mavlink_raw_imu_t ), typeof( mavlink_raw_pressure_t ), typeof( mavlink_attitude_t ), typeof( mavlink_local_position_t ), typeof( mavlink_gps_raw_t ), typeof( mavlink_global_position_t ), typeof( mavlink_sys_status_t ), typeof( mavlink_rc_channels_raw_t ), typeof( mavlink_rc_channels_scaled_t ), typeof( mavlink_servo_output_raw_t ), typeof( mavlink_scaled_pressure_t ), typeof( mavlink_waypoint_t ), typeof( mavlink_waypoint_request_t ), typeof( mavlink_waypoint_set_current_t ), typeof( mavlink_waypoint_current_t ), typeof( mavlink_waypoint_request_list_t ), typeof( mavlink_waypoint_count_t ), typeof( mavlink_waypoint_clear_all_t ), typeof( mavlink_waypoint_reached_t ), typeof( mavlink_waypoint_ack_t ), typeof( mavlink_gps_set_global_origin_t ), typeof( mavlink_gps_local_origin_set_t ), typeof( mavlink_local_position_setpoint_set_t ), typeof( mavlink_local_position_setpoint_t ), typeof( mavlink_control_status_t ), typeof( mavlink_safety_set_allowed_area_t ), typeof( mavlink_safety_allowed_area_t ), typeof( mavlink_set_roll_pitch_yaw_thrust_t ), typeof( mavlink_set_roll_pitch_yaw_speed_thrust_t ), typeof( mavlink_roll_pitch_yaw_thrust_setpoint_t ), typeof( mavlink_roll_pitch_yaw_speed_thrust_setpoint_t ), null, null, null, typeof( mavlink_nav_controller_output_t ), typeof( mavlink_position_target_t ), typeof( mavlink_state_correction_t ), typeof( mavlink_set_altitude_t ), typeof( mavlink_request_data_stream_t ), typeof( mavlink_hil_state_t ), typeof( mavlink_hil_controls_t ), typeof( mavlink_manual_control_t ), typeof( mavlink_rc_channels_override_t ), null, null, typeof( mavlink_global_position_int_t ), typeof( mavlink_vfr_hud_t ), typeof( mavlink_command_t ), typeof( mavlink_command_ack_t ), null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, typeof( mavlink_optical_flow_t ), null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, typeof( mavlink_object_detection_event_t ), null, null, null, null, null, null, null, null, null, typeof( mavlink_sensor_offsets_t ), typeof( mavlink_set_mag_offsets_t ), typeof( mavlink_meminfo_t ), typeof( mavlink_ap_adc_t ), typeof( mavlink_digicam_configure_t ), typeof( mavlink_digicam_control_t ), typeof( mavlink_mount_configure_t ), typeof( mavlink_mount_control_t ), typeof( mavlink_mount_status_t ), null, typeof( mavlink_fence_point_t ), typeof( mavlink_fence_fetch_point_t ), typeof( mavlink_fence_status_t ), typeof( mavlink_ahrs_t ), typeof( mavlink_simstate_t ), typeof( mavlink_hwstatus_t ), typeof( mavlink_radio_t ), null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, null, typeof( mavlink_debug_vect_t ), typeof( mavlink_named_value_float_t ), typeof( mavlink_named_value_int_t ), typeof( mavlink_statustext_t ), typeof( mavlink_debug_t )};
|
||||
|
||||
|
@ -519,10 +519,12 @@ namespace ArdupilotMega
|
|||
public byte remrssi;
|
||||
/// <summary> how full the tx buffer is as a percentage </summary>
|
||||
public byte txbuf;
|
||||
/// <summary> background noise level </summary>
|
||||
public byte noise;
|
||||
/// <summary> remote background noise level </summary>
|
||||
public byte remnoise;
|
||||
/// <summary> receive errors </summary>
|
||||
public UInt16 rxerrors;
|
||||
/// <summary> serial errors </summary>
|
||||
public UInt16 serrors;
|
||||
/// <summary> count of error corrected packets </summary>
|
||||
public UInt16 fixedp;
|
||||
|
||||
|
@ -1830,5 +1832,5 @@ namespace ArdupilotMega
|
|||
};
|
||||
|
||||
}
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
|
|
|
@ -1524,6 +1524,8 @@ namespace ArdupilotMega
|
|||
var baseurl = ConfigurationManager.AppSettings["UpdateLocation"];
|
||||
string path = Path.GetFileName(Application.ExecutablePath);
|
||||
|
||||
path = "version.txt";
|
||||
|
||||
// Create a request using a URL that can receive a post.
|
||||
string requestUriString = baseurl + path;
|
||||
log.Debug("Checking for update at: " + requestUriString);
|
||||
|
@ -1531,7 +1533,7 @@ namespace ArdupilotMega
|
|||
webRequest.Timeout = 5000;
|
||||
|
||||
// Set the Method property of the request to POST.
|
||||
webRequest.Method = "HEAD";
|
||||
webRequest.Method = "GET";
|
||||
|
||||
((HttpWebRequest)webRequest).IfModifiedSince = File.GetLastWriteTimeUtc(path);
|
||||
|
||||
|
@ -1549,24 +1551,34 @@ namespace ArdupilotMega
|
|||
{
|
||||
var fi = new FileInfo(path);
|
||||
|
||||
string CurrentEtag = "";
|
||||
string LocalVersion = "";
|
||||
string WebVersion = "";
|
||||
|
||||
if (File.Exists(path + ".etag"))
|
||||
if (File.Exists(path))
|
||||
{
|
||||
using (Stream fs = File.OpenRead(path + ".etag"))
|
||||
using (Stream fs = File.OpenRead(path))
|
||||
{
|
||||
using (StreamReader sr = new StreamReader(fs))
|
||||
{
|
||||
CurrentEtag = sr.ReadLine();
|
||||
LocalVersion = sr.ReadLine();
|
||||
sr.Close();
|
||||
}
|
||||
fs.Close();
|
||||
}
|
||||
}
|
||||
|
||||
log.Info("New file Check: " + fi.Length + " vs " + response.ContentLength + " " + response.Headers[HttpResponseHeader.ETag] + " vs " + CurrentEtag);
|
||||
using (StreamReader sr = new StreamReader(response.GetResponseStream()))
|
||||
{
|
||||
WebVersion = sr.ReadLine();
|
||||
|
||||
if (fi.Length != response.ContentLength || response.Headers[HttpResponseHeader.ETag] != CurrentEtag)
|
||||
sr.Close();
|
||||
}
|
||||
|
||||
|
||||
|
||||
log.Info("New file Check: local " + LocalVersion + " vs Remote " + WebVersion);
|
||||
|
||||
if (LocalVersion != WebVersion)
|
||||
{
|
||||
shouldGetFile = true;
|
||||
}
|
||||
|
@ -1889,9 +1901,13 @@ namespace ArdupilotMega
|
|||
}
|
||||
if (keyData == (Keys.Control | Keys.A)) // test
|
||||
{
|
||||
Form temp = new Form();
|
||||
Control frm = new _3DRradio();
|
||||
ThemeManager.ApplyThemeTo(frm);
|
||||
frm.Show();
|
||||
temp.Controls.Add(frm);
|
||||
temp.Size = frm.Size;
|
||||
frm.Dock = DockStyle.Fill;
|
||||
ThemeManager.ApplyThemeTo(temp);
|
||||
temp.Show();
|
||||
return true;
|
||||
}
|
||||
if (keyData == (Keys.Control | Keys.W)) // test
|
||||
|
|
|
@ -0,0 +1,167 @@
|
|||
using System;
|
||||
using System.Collections.Generic;
|
||||
using System.Linq;
|
||||
using System.Text;
|
||||
|
||||
namespace ArdupilotMega
|
||||
{
|
||||
public partial class MAVLink
|
||||
{
|
||||
#if !MAVLINK10
|
||||
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
|
||||
};
|
||||
|
||||
public enum MAV_ACTION
|
||||
{
|
||||
MAV_ACTION_HOLD = 0,
|
||||
MAV_ACTION_MOTORS_START = 1,
|
||||
MAV_ACTION_LAUNCH = 2,
|
||||
MAV_ACTION_RETURN = 3,
|
||||
MAV_ACTION_EMCY_LAND = 4,
|
||||
MAV_ACTION_EMCY_KILL = 5,
|
||||
MAV_ACTION_CONFIRM_KILL = 6,
|
||||
MAV_ACTION_CONTINUE = 7,
|
||||
MAV_ACTION_MOTORS_STOP = 8,
|
||||
MAV_ACTION_HALT = 9,
|
||||
MAV_ACTION_SHUTDOWN = 10,
|
||||
MAV_ACTION_REBOOT = 11,
|
||||
MAV_ACTION_SET_MANUAL = 12,
|
||||
MAV_ACTION_SET_AUTO = 13,
|
||||
MAV_ACTION_STORAGE_READ = 14,
|
||||
MAV_ACTION_STORAGE_WRITE = 15,
|
||||
MAV_ACTION_CALIBRATE_RC = 16,
|
||||
MAV_ACTION_CALIBRATE_GYRO = 17,
|
||||
MAV_ACTION_CALIBRATE_MAG = 18,
|
||||
MAV_ACTION_CALIBRATE_ACC = 19,
|
||||
MAV_ACTION_CALIBRATE_PRESSURE = 20,
|
||||
MAV_ACTION_REC_START = 21,
|
||||
MAV_ACTION_REC_PAUSE = 22,
|
||||
MAV_ACTION_REC_STOP = 23,
|
||||
MAV_ACTION_TAKEOFF = 24,
|
||||
MAV_ACTION_NAVIGATE = 25,
|
||||
MAV_ACTION_LAND = 26,
|
||||
MAV_ACTION_LOITER = 27,
|
||||
MAV_ACTION_SET_ORIGIN = 28,
|
||||
MAV_ACTION_RELAY_ON = 29,
|
||||
MAV_ACTION_RELAY_OFF = 30,
|
||||
MAV_ACTION_GET_IMAGE = 31,
|
||||
MAV_ACTION_VIDEO_START = 32,
|
||||
MAV_ACTION_VIDEO_STOP = 33,
|
||||
MAV_ACTION_RESET_MAP = 34,
|
||||
MAV_ACTION_RESET_PLAN = 35,
|
||||
MAV_ACTION_DELAY_BEFORE_COMMAND = 36,
|
||||
MAV_ACTION_ASCEND_AT_RATE = 37,
|
||||
MAV_ACTION_CHANGE_MODE = 38,
|
||||
MAV_ACTION_LOITER_MAX_TURNS = 39,
|
||||
MAV_ACTION_LOITER_MAX_TIME = 40,
|
||||
MAV_ACTION_START_HILSIM = 41,
|
||||
MAV_ACTION_STOP_HILSIM = 42,
|
||||
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
|
||||
};
|
||||
|
||||
public enum MAV_STATE
|
||||
{
|
||||
MAV_STATE_UNINIT = 0,
|
||||
MAV_STATE_BOOT,
|
||||
MAV_STATE_CALIBRATING,
|
||||
MAV_STATE_STANDBY,
|
||||
MAV_STATE_ACTIVE,
|
||||
MAV_STATE_CRITICAL,
|
||||
MAV_STATE_EMERGENCY,
|
||||
MAV_STATE_HILSIM,
|
||||
MAV_STATE_POWEROFF
|
||||
};
|
||||
|
||||
public enum MAV_NAV
|
||||
{
|
||||
MAV_NAV_GROUNDED = 0,
|
||||
MAV_NAV_LIFTOFF,
|
||||
MAV_NAV_HOLD,
|
||||
MAV_NAV_WAYPOINT,
|
||||
MAV_NAV_VECTOR,
|
||||
MAV_NAV_RETURNING,
|
||||
MAV_NAV_LANDING,
|
||||
MAV_NAV_LOST,
|
||||
MAV_NAV_LOITER,
|
||||
MAV_NAV_FREE_DRIFT
|
||||
};
|
||||
|
||||
public enum MAV_TYPE
|
||||
{
|
||||
MAV_GENERIC = 0,
|
||||
MAV_FIXED_WING = 1,
|
||||
MAV_QUADROTOR = 2,
|
||||
MAV_COAXIAL = 3,
|
||||
MAV_HELICOPTER = 4,
|
||||
MAV_GROUND = 5,
|
||||
OCU = 6,
|
||||
MAV_AIRSHIP = 7,
|
||||
MAV_FREE_BALLOON = 8,
|
||||
MAV_ROCKET = 9,
|
||||
UGV_GROUND_ROVER = 10,
|
||||
UGV_SURFACE_SHIP = 11
|
||||
};
|
||||
|
||||
public enum MAV_AUTOPILOT_TYPE
|
||||
{
|
||||
MAV_AUTOPILOT_GENERIC = 0,
|
||||
MAV_AUTOPILOT_PIXHAWK = 1,
|
||||
MAV_AUTOPILOT_SLUGS = 2,
|
||||
MAV_AUTOPILOT_ARDUPILOTMEGA = 3,
|
||||
MAV_AUTOPILOT_NONE = 4
|
||||
};
|
||||
|
||||
public enum MAV_COMPONENT
|
||||
{
|
||||
MAV_COMP_ID_GPS,
|
||||
MAV_COMP_ID_WAYPOINTPLANNER,
|
||||
MAV_COMP_ID_BLOBTRACKER,
|
||||
MAV_COMP_ID_PATHPLANNER,
|
||||
MAV_COMP_ID_AIRSLAM,
|
||||
MAV_COMP_ID_MAPPER,
|
||||
MAV_COMP_ID_CAMERA,
|
||||
MAV_COMP_ID_IMU = 200,
|
||||
MAV_COMP_ID_IMU_2 = 201,
|
||||
MAV_COMP_ID_IMU_3 = 202,
|
||||
MAV_COMP_ID_UDP_BRIDGE = 240,
|
||||
MAV_COMP_ID_UART_BRIDGE = 241,
|
||||
MAV_COMP_ID_SYSTEM_CONTROL = 250
|
||||
};
|
||||
|
||||
public enum MAV_FRAME
|
||||
{
|
||||
GLOBAL = 0,
|
||||
LOCAL = 1,
|
||||
MISSION = 2,
|
||||
GLOBAL_RELATIVE_ALT = 3,
|
||||
LOCAL_ENU = 4
|
||||
};
|
||||
|
||||
#endif
|
||||
}
|
||||
}
|
|
@ -38,6 +38,8 @@ namespace ArdupilotMega
|
|||
|
||||
Hashtable data = new Hashtable();
|
||||
|
||||
PointLatLngAlt homepos = new PointLatLngAlt();
|
||||
|
||||
public MavlinkLog()
|
||||
{
|
||||
InitializeComponent();
|
||||
|
@ -576,15 +578,16 @@ namespace ArdupilotMega
|
|||
|
||||
|
||||
OpenFileDialog openFileDialog1 = new OpenFileDialog();
|
||||
try
|
||||
{
|
||||
// openFileDialog1.InitialDirectory = Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + @"logs" + Path.DirectorySeparatorChar;
|
||||
}
|
||||
catch { } // incase dir doesnt exist
|
||||
openFileDialog1.Filter = "*.tlog|*.tlog";
|
||||
openFileDialog1.FilterIndex = 2;
|
||||
openFileDialog1.RestoreDirectory = true;
|
||||
openFileDialog1.Multiselect = false;
|
||||
try
|
||||
{
|
||||
openFileDialog1.InitialDirectory = Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + @"logs" + Path.DirectorySeparatorChar;
|
||||
}
|
||||
catch { } // incase dir doesnt exist
|
||||
|
||||
|
||||
if (openFileDialog1.ShowDialog() == DialogResult.OK)
|
||||
{
|
||||
|
@ -781,6 +784,8 @@ namespace ArdupilotMega
|
|||
|
||||
MavlinkInterface.packets.Initialize(); // clear
|
||||
|
||||
CurrentState cs = new CurrentState();
|
||||
|
||||
// to get first packet time
|
||||
MavlinkInterface.readPacket();
|
||||
|
||||
|
@ -793,6 +798,10 @@ namespace ArdupilotMega
|
|||
|
||||
byte[] packet = MavlinkInterface.readPacket();
|
||||
|
||||
cs.datetime = MavlinkInterface.lastlogread;
|
||||
|
||||
cs.UpdateCurrentSettings(null, true, MavlinkInterface);
|
||||
|
||||
object data = MavlinkInterface.DebugPacket(packet, false);
|
||||
|
||||
if (data == null)
|
||||
|
@ -864,6 +873,8 @@ namespace ArdupilotMega
|
|||
|
||||
addMagField(ref options);
|
||||
|
||||
addDistHome(ref options);
|
||||
|
||||
}
|
||||
catch (Exception ex) { log.Info(ex.ToString()); }
|
||||
|
||||
|
@ -871,10 +882,14 @@ namespace ArdupilotMega
|
|||
//options.Sort(delegate(string c1, string c2) { return String.Compare(c1.Substring(0,c1.IndexOf('.')),c2.Substring(0,c2.IndexOf('.')));});
|
||||
|
||||
// this needs sorting
|
||||
string lastitem = "";
|
||||
foreach (string item in options)
|
||||
{
|
||||
var items = item.Split('.');
|
||||
if (items[0] != lastitem)
|
||||
AddHeader(selectform, items[0].Replace("mavlink_","").Replace("_t","").ToUpper());
|
||||
AddDataOption(selectform, items[1] + " " + items[0]);
|
||||
lastitem = items[0];
|
||||
}
|
||||
|
||||
selectform.Show();
|
||||
|
@ -886,6 +901,29 @@ namespace ArdupilotMega
|
|||
return selection;
|
||||
}
|
||||
|
||||
void dospecial(string PacketName)
|
||||
{
|
||||
string test = @"0; float test = (float)Sin(55) + 10;
|
||||
test += (float)sin(45);
|
||||
return test;
|
||||
";
|
||||
|
||||
object answer = CodeGen.runCode(test);
|
||||
|
||||
Console.WriteLine(answer);
|
||||
}
|
||||
|
||||
PointPairList GetValuesForField(string name)
|
||||
{
|
||||
// eg RAW_IMU.xmag to "xmag mavlink_raw_imu_t"
|
||||
|
||||
string[] items = name.ToLower().Split(new char[] {'.',' '});
|
||||
|
||||
PointPairList list = ((PointPairList)this.data[items[1] + " mavlink_" + items[0] + "_t"]);
|
||||
|
||||
return list;
|
||||
}
|
||||
|
||||
void addMagField(ref List<string> options)
|
||||
{
|
||||
string field = "mag_field Custom";
|
||||
|
@ -913,6 +951,72 @@ namespace ArdupilotMega
|
|||
}
|
||||
}
|
||||
|
||||
void addDistHome(ref List<string> options)
|
||||
{
|
||||
string field = "dist_home Custom";
|
||||
|
||||
options.Add("Custom.dist_home");
|
||||
|
||||
this.data[field] = new PointPairList();
|
||||
|
||||
PointLatLngAlt home = new PointLatLngAlt();
|
||||
|
||||
PointPairList list = ((PointPairList)this.data[field]);
|
||||
|
||||
PointPairList listfix = ((PointPairList)this.data["fix_type mavlink_gps_raw_t"]);
|
||||
PointPairList listx = ((PointPairList)this.data["lat mavlink_gps_raw_t"]);
|
||||
PointPairList listy = ((PointPairList)this.data["lon mavlink_gps_raw_t"]);
|
||||
PointPairList listz = ((PointPairList)this.data["alt mavlink_gps_raw_t"]);
|
||||
|
||||
for (int a = 0; a < listfix.Count; a++)
|
||||
{
|
||||
if (listfix[a].Y == 2)
|
||||
{
|
||||
home = new PointLatLngAlt(listx[a].Y, listy[a].Y, listz[a].Y,"Home");
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
//(float)Math.Sqrt(Math.Pow(mx, 2) + Math.Pow(my, 2) + Math.Pow(mz, 2));
|
||||
|
||||
for (int a = 0; a < listx.Count; a++)
|
||||
{
|
||||
|
||||
double ans = home.GetDistance(new PointLatLngAlt(listx[a].Y, listy[a].Y, listz[a].Y, "Point"));
|
||||
|
||||
//Console.WriteLine("{0} {1} {2} {3}", ans, listx[a].Y, listy[a].Y, listz[a].Y);
|
||||
|
||||
list.Add(listx[a].X, ans);
|
||||
}
|
||||
}
|
||||
|
||||
private void AddHeader(Form selectform, string Name)
|
||||
{
|
||||
System.Windows.Forms.Label lbl_head = new System.Windows.Forms.Label();
|
||||
|
||||
log.Info("Add Header " + Name);
|
||||
|
||||
lbl_head.Text = Name;
|
||||
lbl_head.Name = Name;
|
||||
lbl_head.Location = new System.Drawing.Point(x, y);
|
||||
lbl_head.Size = new System.Drawing.Size(100, 20);
|
||||
|
||||
selectform.Controls.Add(lbl_head);
|
||||
|
||||
Application.DoEvents();
|
||||
|
||||
x += 0;
|
||||
y += 20;
|
||||
|
||||
if (y > selectform.Height - 60)
|
||||
{
|
||||
x += 100;
|
||||
y = 10;
|
||||
|
||||
selectform.Width = x + 100;
|
||||
}
|
||||
}
|
||||
|
||||
private void AddDataOption(Form selectform, string Name)
|
||||
{
|
||||
|
||||
|
@ -925,6 +1029,7 @@ namespace ArdupilotMega
|
|||
chk_box.Location = new System.Drawing.Point(x, y);
|
||||
chk_box.Size = new System.Drawing.Size(100, 20);
|
||||
chk_box.CheckedChanged += new EventHandler(chk_box_CheckedChanged);
|
||||
chk_box.MouseUp += new MouseEventHandler(chk_box_MouseUp);
|
||||
|
||||
selectform.Controls.Add(chk_box);
|
||||
|
||||
|
@ -933,7 +1038,7 @@ namespace ArdupilotMega
|
|||
x += 0;
|
||||
y += 20;
|
||||
|
||||
if (y > selectform.Height - 50)
|
||||
if (y > selectform.Height - 60)
|
||||
{
|
||||
x += 100;
|
||||
y = 10;
|
||||
|
@ -942,7 +1047,26 @@ namespace ArdupilotMega
|
|||
}
|
||||
}
|
||||
|
||||
void chk_box_MouseUp(object sender, MouseEventArgs e)
|
||||
{
|
||||
if (e.Button == System.Windows.Forms.MouseButtons.Right)
|
||||
{
|
||||
// dont action a already draw item
|
||||
if (!((CheckBox)sender).Checked)
|
||||
{
|
||||
rightclick = true;
|
||||
((CheckBox)sender).Checked = true;
|
||||
}
|
||||
else
|
||||
{
|
||||
((CheckBox)sender).Checked = false;
|
||||
}
|
||||
rightclick = false;
|
||||
}
|
||||
}
|
||||
|
||||
int colorStep = 0;
|
||||
bool rightclick = false;
|
||||
|
||||
void chk_box_CheckedChanged(object sender, EventArgs e)
|
||||
{
|
||||
|
@ -976,11 +1100,13 @@ namespace ArdupilotMega
|
|||
|
||||
myCurve.GetRange(out xMin, out xMax, out yMin, out yMax, true, false, zg1.GraphPane);
|
||||
|
||||
if (yMin > 900 && yMax < 2100 && yMin < 2100)
|
||||
if (rightclick || (yMin > 850 && yMax < 2100 && yMin < 2100))
|
||||
{
|
||||
myCurve.IsY2Axis = true;
|
||||
myCurve.YAxisIndex = 0;
|
||||
zg1.GraphPane.Y2Axis.IsVisible = true;
|
||||
|
||||
myCurve.Label.Text = myCurve.Label.Text + "-R";
|
||||
}
|
||||
}
|
||||
else
|
||||
|
@ -1001,6 +1127,8 @@ namespace ArdupilotMega
|
|||
// fix new line types
|
||||
ThemeManager.ApplyThemeTo(this);
|
||||
|
||||
zg1.GraphPane.XAxis.AxisGap = 0;
|
||||
|
||||
zg1.Invalidate();
|
||||
zg1.AxisChange();
|
||||
}
|
||||
|
@ -1024,18 +1152,10 @@ namespace ArdupilotMega
|
|||
x = 10;
|
||||
y = 10;
|
||||
|
||||
{
|
||||
CheckBox chk_box = new CheckBox();
|
||||
chk_box.Text = "Logarithmic";
|
||||
chk_box.Name = "Logarithmic";
|
||||
chk_box.Location = new System.Drawing.Point(x, y);
|
||||
chk_box.Size = new System.Drawing.Size(100, 20);
|
||||
//chk_box.CheckedChanged += new EventHandler(chk_log_CheckedChanged);
|
||||
|
||||
selectform.Controls.Add(chk_box);
|
||||
}
|
||||
|
||||
y += 20;
|
||||
AddHeader(selectform, "Left Click");
|
||||
AddHeader(selectform, "Left Axis");
|
||||
AddHeader(selectform, "Right Click");
|
||||
AddHeader(selectform, "Right Axis");
|
||||
|
||||
ThemeManager.ApplyThemeTo(selectform);
|
||||
|
||||
|
|
|
@ -7,10 +7,10 @@ del installer.wixobj
|
|||
"%wix%\bin\candle" installer.wxs -ext WiXNetFxExtension -ext WixDifxAppExtension -ext WixUIExtension.dll -ext WixUtilExtension
|
||||
|
||||
|
||||
"%wix%\bin\light" installer.wixobj "%wix%\bin\difxapp_x86.wixlib" -o APMPlannerx86.msi -ext WiXNetFxExtension -ext WixDifxAppExtension -ext WixUIExtension.dll -ext WixUtilExtension
|
||||
"%wix%\bin\light" installer.wixobj "%wix%\bin\difxapp_x86.wixlib" -o APMPlanner32.msi -ext WiXNetFxExtension -ext WixDifxAppExtension -ext WixUIExtension.dll -ext WixUtilExtension
|
||||
|
||||
|
||||
"%wix%\bin\light" installer.wixobj "%wix%\bin\difxapp_x64.wixlib" -o APMPlannerx64.msi -ext WiXNetFxExtension -ext WixDifxAppExtension -ext WixUIExtension.dll -ext WixUtilExtension
|
||||
"%wix%\bin\light" installer.wixobj "%wix%\bin\difxapp_x64.wixlib" -o APMPlanner64.msi -ext WiXNetFxExtension -ext WixDifxAppExtension -ext WixUIExtension.dll -ext WixUtilExtension
|
||||
|
||||
|
||||
pause
|
||||
|
|
|
@ -2,11 +2,19 @@
|
|||
<Wix xmlns="http://schemas.microsoft.com/wix/2006/wi" xmlns:netfx="http://schemas.microsoft.com/wix/NetFxExtension" xmlns:difx="http://schemas.microsoft.com/wix/DifxAppExtension">
|
||||
|
||||
|
||||
<Product Id="{625389D7-EB3C-4d77-A5F6-A285CF99437D}" Name="APM Planner" Language="1033" Version="1.1.60" Manufacturer="Michael Oborne" UpgradeCode="{625389D7-EB3C-4d77-A5F6-A285CF99437D}">
|
||||
<Product Id="*" Name="APM Planner" Language="1033" Version="1.1.63" Manufacturer="Michael Oborne" UpgradeCode="{625389D7-EB3C-4d77-A5F6-A285CF99437D}">
|
||||
|
||||
<Package Description="APM Planner Installer" Comments="Apm Planner Installer" Manufacturer="Michael Oborne" InstallerVersion="200" Compressed="yes" />
|
||||
|
||||
<MajorUpgrade DowngradeErrorMessage="A later version of [ProductName] is already installed. Setup will now exit."/>
|
||||
|
||||
<Upgrade Id="{625389D7-EB3C-4d77-A5F6-A285CF99437D}">
|
||||
<UpgradeVersion OnlyDetect="yes" Minimum="1.1.63" Property="NEWERVERSIONDETECTED" IncludeMinimum="no" />
|
||||
<UpgradeVersion OnlyDetect="no" Maximum="1.1.63" Property="OLDERVERSIONBEINGUPGRADED" IncludeMaximum="no" />
|
||||
</Upgrade>
|
||||
|
||||
<InstallExecuteSequence>
|
||||
<RemoveExistingProducts After="InstallInitialize" />
|
||||
</InstallExecuteSequence>
|
||||
|
||||
<PropertyRef Id="NETFRAMEWORK35" />
|
||||
|
||||
|
@ -23,100 +31,221 @@
|
|||
<Permission User="Everyone" GenericAll="yes" />
|
||||
</CreateFolder>
|
||||
</Component>
|
||||
<Component Id="_comp1" Guid="34295c8e-0d23-4735-b56d-d2b6652756e5">
|
||||
<Component Id="_comp1" Guid="27583d32-d5cc-422a-a1d9-22fcb0aaf864">
|
||||
<File Id="_2" Source="..\bin\release\AeroSimRCAPMHil.zip" />
|
||||
<File Id="_3" Source="..\bin\release\alglibnet2.dll" />
|
||||
<File Id="_4" Source="..\bin\release\arducopter-xplane.zip" />
|
||||
<File Id="_5" Source="..\bin\release\ArdupilotMegaPlanner.exe" />
|
||||
<File Id="_6" Source="..\bin\release\ArdupilotMegaPlanner.exe.config" />
|
||||
<File Id="_7" Source="..\bin\release\ArdupilotMegaPlanner.pdb" />
|
||||
<File Id="_8" Source="..\bin\release\block_plane_0.dae" />
|
||||
<File Id="_9" Source="..\bin\release\BSE.Windows.Forms.dll" />
|
||||
<File Id="_10" Source="..\bin\release\Core.dll" />
|
||||
<File Id="_11" Source="..\bin\release\dataflashlog.xml" />
|
||||
<File Id="_12" Source="..\bin\release\DirectShowLib-2005.dll" />
|
||||
<File Id="_13" Source="..\bin\release\GMap.NET.Core.dll" />
|
||||
<File Id="_14" Source="..\bin\release\GMap.NET.WindowsForms.dll" />
|
||||
<File Id="_15" Source="..\bin\release\hud.html" />
|
||||
<File Id="_16" Source="..\bin\release\ICSharpCode.SharpZipLib.dll" />
|
||||
<File Id="_17" Source="..\bin\release\Ionic.Zip.Reduced.dll" />
|
||||
<File Id="_18" Source="..\bin\release\IronPython.dll" />
|
||||
<File Id="_19" Source="..\bin\release\IronPython.Modules.dll" />
|
||||
<File Id="_20" Source="..\bin\release\JSBSim.exe" />
|
||||
<File Id="_21" Source="..\bin\release\KMLib.dll" />
|
||||
<File Id="_22" Source="..\bin\release\log4net.dll" />
|
||||
<File Id="_23" Source="..\bin\release\mavcmd.xml" />
|
||||
<File Id="_24" Source="..\bin\release\MAVLink.xml" />
|
||||
<File Id="_25" Source="..\bin\release\MetaDataExtractor.dll" />
|
||||
<File Id="_26" Source="..\bin\release\Microsoft.Dynamic.dll" />
|
||||
<File Id="_27" Source="..\bin\release\Microsoft.Scripting.Core.dll" />
|
||||
<File Id="_28" Source="..\bin\release\Microsoft.Scripting.Debugging.dll" />
|
||||
<File Id="_29" Source="..\bin\release\Microsoft.Scripting.dll" />
|
||||
<File Id="_30" Source="..\bin\release\Microsoft.Scripting.ExtensionAttribute.dll" />
|
||||
<File Id="_31" Source="..\bin\release\netDxf.dll" />
|
||||
<File Id="_32" Source="..\bin\release\OpenTK.dll" />
|
||||
<File Id="_33" Source="..\bin\release\OpenTK.GLControl.dll" />
|
||||
<File Id="_34" Source="..\bin\release\quadhil.xml" />
|
||||
<File Id="_35" Source="..\bin\release\SharpKml.dll" />
|
||||
<File Id="_36" Source="..\bin\release\System.Data.SQLite.dll" />
|
||||
<File Id="_37" Source="..\bin\release\System.Speech.dll" />
|
||||
<File Id="_38" Source="..\bin\release\Updater.exe" />
|
||||
<File Id="_39" Source="..\bin\release\Updater.exe.config" />
|
||||
<File Id="_40" Source="..\bin\release\Updater.pdb" />
|
||||
<File Id="_41" Source="..\bin\release\ZedGraph.dll" />
|
||||
<File Id="_4" Source="..\bin\release\ArduCopter-sitl.exe" />
|
||||
<File Id="_5" Source="..\bin\release\arducopter-xplane.zip" />
|
||||
<File Id="_6" Source="..\bin\release\ArduCopter.exe" />
|
||||
<File Id="_7" Source="..\bin\release\ArdupilotMegaPlanner.exe" />
|
||||
<File Id="_8" Source="..\bin\release\ArdupilotMegaPlanner.exe.config" />
|
||||
<File Id="_9" Source="..\bin\release\ArdupilotMegaPlanner.pdb" />
|
||||
<File Id="_10" Source="..\bin\release\ArduPlane-sitl.exe" />
|
||||
<File Id="_11" Source="..\bin\release\ArduPlane.exe" />
|
||||
<File Id="_12" Source="..\bin\release\block_plane_0.dae" />
|
||||
<File Id="_13" Source="..\bin\release\BSE.Windows.Forms.dll" />
|
||||
<File Id="_14" Source="..\bin\release\Core.dll" />
|
||||
<File Id="_15" Source="..\bin\release\cygwin1.dll" />
|
||||
<File Id="_16" Source="..\bin\release\dataflashlog.xml" />
|
||||
<File Id="_17" Source="..\bin\release\DirectShowLib-2005.dll" />
|
||||
<File Id="_18" Source="..\bin\release\eeprom.bin" />
|
||||
<File Id="_19" Source="..\bin\release\GMap.NET.Core.dll" />
|
||||
<File Id="_20" Source="..\bin\release\GMap.NET.WindowsForms.dll" />
|
||||
<File Id="_21" Source="..\bin\release\hud.html" />
|
||||
<File Id="_22" Source="..\bin\release\ICSharpCode.SharpZipLib.dll" />
|
||||
<File Id="_23" Source="..\bin\release\Ionic.Zip.Reduced.dll" />
|
||||
<File Id="_24" Source="..\bin\release\IronPython.dll" />
|
||||
<File Id="_25" Source="..\bin\release\IronPython.Modules.dll" />
|
||||
<File Id="_26" Source="..\bin\release\JSBSim.exe" />
|
||||
<File Id="_27" Source="..\bin\release\KMLib.dll" />
|
||||
<File Id="_28" Source="..\bin\release\log4net.dll" />
|
||||
<File Id="_29" Source="..\bin\release\mavcmd.xml" />
|
||||
<File Id="_30" Source="..\bin\release\MAVLink.xml" />
|
||||
<File Id="_31" Source="..\bin\release\MetaDataExtractor.dll" />
|
||||
<File Id="_32" Source="..\bin\release\Microsoft.DirectX.DirectInput.dll" />
|
||||
<File Id="_33" Source="..\bin\release\Microsoft.DirectX.dll" />
|
||||
<File Id="_34" Source="..\bin\release\Microsoft.Dynamic.dll" />
|
||||
<File Id="_35" Source="..\bin\release\Microsoft.Scripting.Core.dll" />
|
||||
<File Id="_36" Source="..\bin\release\Microsoft.Scripting.Debugging.dll" />
|
||||
<File Id="_37" Source="..\bin\release\Microsoft.Scripting.dll" />
|
||||
<File Id="_38" Source="..\bin\release\Microsoft.Scripting.ExtensionAttribute.dll" />
|
||||
<File Id="_39" Source="..\bin\release\netDxf.dll" />
|
||||
<File Id="_40" Source="..\bin\release\OpenTK.dll" />
|
||||
<File Id="_41" Source="..\bin\release\OpenTK.GLControl.dll" />
|
||||
<File Id="_42" Source="..\bin\release\quadhil.xml" />
|
||||
<File Id="_43" Source="..\bin\release\serialsent.raw" />
|
||||
<File Id="_44" Source="..\bin\release\SharpKml.dll" />
|
||||
<File Id="_45" Source="..\bin\release\System.Data.SQLite.dll" />
|
||||
<File Id="_46" Source="..\bin\release\System.Speech.dll" />
|
||||
<File Id="_47" Source="..\bin\release\Updater.exe" />
|
||||
<File Id="_48" Source="..\bin\release\Updater.exe.config" />
|
||||
<File Id="_49" Source="..\bin\release\Updater.pdb" />
|
||||
<File Id="_50" Source="..\bin\release\version.exe" />
|
||||
<File Id="_51" Source="..\bin\release\version.txt" />
|
||||
<File Id="_52" Source="..\bin\release\ZedGraph.dll" />
|
||||
</Component>
|
||||
<Directory Id="Driver41" Name="Driver">
|
||||
<Component Id="_comp42" Guid="3975a290-2f19-4aa9-97b9-37d45672d063">
|
||||
<File Id="_43" Source="..\bin\release\Driver\Arduino MEGA 2560.inf" />
|
||||
<Directory Id="aircraft52" Name="aircraft">
|
||||
<Component Id="_comp53" Guid="f064b576-e9b4-41d2-8b08-49172818c653">
|
||||
<File Id="_54" Source="..\bin\release\aircraft\placeholder.txt" />
|
||||
</Component>
|
||||
<Directory Id="arducopter54" Name="arducopter">
|
||||
<Component Id="_comp55" Guid="4d8cdb81-fab2-4b24-ad08-cefb45253f27">
|
||||
<File Id="_56" Source="..\bin\release\aircraft\arducopter\arducopter-set.xml" />
|
||||
<File Id="_57" Source="..\bin\release\aircraft\arducopter\arducopter.jpg" />
|
||||
<File Id="_58" Source="..\bin\release\aircraft\arducopter\arducopter.xml" />
|
||||
<File Id="_59" Source="..\bin\release\aircraft\arducopter\initfile.xml" />
|
||||
<File Id="_60" Source="..\bin\release\aircraft\arducopter\plus_quad2-set.xml" />
|
||||
<File Id="_61" Source="..\bin\release\aircraft\arducopter\plus_quad2.xml" />
|
||||
<File Id="_62" Source="..\bin\release\aircraft\arducopter\quad.nas" />
|
||||
<File Id="_63" Source="..\bin\release\aircraft\arducopter\README" />
|
||||
</Component>
|
||||
<Directory Id="data63" Name="data">
|
||||
<Component Id="_comp64" Guid="498fb8f9-f963-489b-bffd-605d6f70d7b1">
|
||||
<File Id="_65" Source="..\bin\release\aircraft\arducopter\data\arducopter_half_step.txt" />
|
||||
<File Id="_66" Source="..\bin\release\aircraft\arducopter\data\arducopter_step.txt" />
|
||||
<File Id="_67" Source="..\bin\release\aircraft\arducopter\data\rw_generic_pylon.ac" />
|
||||
</Component>
|
||||
</Directory>
|
||||
<Directory Id="es_ES43" Name="es-ES">
|
||||
<Component Id="_comp44" Guid="02407d9c-9e9f-4e5d-a48d-d7d9fc0846a7">
|
||||
<File Id="_45" Source="..\bin\release\es-ES\ArdupilotMegaPlanner.resources.dll" />
|
||||
<Directory Id="Engines67" Name="Engines">
|
||||
<Component Id="_comp68" Guid="0844f5b1-b990-43f3-a3e0-1f123d6af8f2">
|
||||
<File Id="_69" Source="..\bin\release\aircraft\arducopter\Engines\a2830-12.xml" />
|
||||
<File Id="_70" Source="..\bin\release\aircraft\arducopter\Engines\prop10x4.5.xml" />
|
||||
</Component>
|
||||
</Directory>
|
||||
<Directory Id="fr45" Name="fr">
|
||||
<Component Id="_comp46" Guid="74e19d89-486a-487d-9053-be1c34b8e7d9">
|
||||
<File Id="_47" Source="..\bin\release\fr\ArdupilotMegaPlanner.resources.dll" />
|
||||
<Directory Id="Models70" Name="Models">
|
||||
<Component Id="_comp71" Guid="cead5c2b-aad8-4b6d-af62-bc3cae0ffe23">
|
||||
<File Id="_72" Source="..\bin\release\aircraft\arducopter\Models\arducopter.ac" />
|
||||
<File Id="_73" Source="..\bin\release\aircraft\arducopter\Models\arducopter.xml" />
|
||||
<File Id="_74" Source="..\bin\release\aircraft\arducopter\Models\plus_quad.ac" />
|
||||
<File Id="_75" Source="..\bin\release\aircraft\arducopter\Models\plus_quad2.ac" />
|
||||
<File Id="_76" Source="..\bin\release\aircraft\arducopter\Models\plus_quad2.xml" />
|
||||
<File Id="_77" Source="..\bin\release\aircraft\arducopter\Models\quad.3ds" />
|
||||
<File Id="_78" Source="..\bin\release\aircraft\arducopter\Models\shareware_output.3ds" />
|
||||
<File Id="_79" Source="..\bin\release\aircraft\arducopter\Models\Untitled.ac" />
|
||||
<File Id="_80" Source="..\bin\release\aircraft\arducopter\Models\Y6_test.ac" />
|
||||
</Component>
|
||||
</Directory>
|
||||
<Directory Id="it_IT47" Name="it-IT">
|
||||
<Component Id="_comp48" Guid="0003cdb4-191e-4771-a098-4e35e5eea039">
|
||||
<File Id="_49" Source="..\bin\release\it-IT\ArdupilotMegaPlanner.resources.dll" />
|
||||
</Directory>
|
||||
<Directory Id="Rascal80" Name="Rascal">
|
||||
<Component Id="_comp81" Guid="63e7949e-2944-4ed6-849b-7a7fa45b08f7">
|
||||
<File Id="_82" Source="..\bin\release\aircraft\Rascal\Rascal-keyboard.xml" />
|
||||
<File Id="_83" Source="..\bin\release\aircraft\Rascal\Rascal-submodels.xml" />
|
||||
<File Id="_84" Source="..\bin\release\aircraft\Rascal\Rascal.xml" />
|
||||
<File Id="_85" Source="..\bin\release\aircraft\Rascal\Rascal110-JSBSim-set.xml" />
|
||||
<File Id="_86" Source="..\bin\release\aircraft\Rascal\Rascal110-JSBSim.xml" />
|
||||
<File Id="_87" Source="..\bin\release\aircraft\Rascal\Rascal110-splash.rgb" />
|
||||
<File Id="_88" Source="..\bin\release\aircraft\Rascal\README.Rascal" />
|
||||
<File Id="_89" Source="..\bin\release\aircraft\Rascal\reset_CMAC.xml" />
|
||||
<File Id="_90" Source="..\bin\release\aircraft\Rascal\thumbnail.jpg" />
|
||||
</Component>
|
||||
<Directory Id="Dialogs90" Name="Dialogs">
|
||||
<Component Id="_comp91" Guid="0e97ffbb-624b-4f93-a2c9-d58462cb82eb">
|
||||
<File Id="_92" Source="..\bin\release\aircraft\Rascal\Dialogs\config.xml" />
|
||||
<File Id="_93" Source="..\bin\release\aircraft\Rascal\Dialogs\config.xml.new" />
|
||||
</Component>
|
||||
</Directory>
|
||||
<Directory Id="m3u49" Name="m3u">
|
||||
<Component Id="_comp50" Guid="fc43d9e6-6966-4682-884f-655b48d2cb21">
|
||||
<File Id="_51" Source="..\bin\release\m3u\both.m3u" />
|
||||
<File Id="_52" Source="..\bin\release\m3u\hud.m3u" />
|
||||
<File Id="_53" Source="..\bin\release\m3u\map.m3u" />
|
||||
<File Id="_54" Source="..\bin\release\m3u\networklink.kml" />
|
||||
<Directory Id="Engines93" Name="Engines">
|
||||
<Component Id="_comp94" Guid="8273a711-606c-47ba-8595-78b5b9b51f84">
|
||||
<File Id="_95" Source="..\bin\release\aircraft\Rascal\Engines\18x8.xml" />
|
||||
<File Id="_96" Source="..\bin\release\aircraft\Rascal\Engines\18x8.xml.new" />
|
||||
<File Id="_97" Source="..\bin\release\aircraft\Rascal\Engines\Zenoah_G-26A.xml" />
|
||||
<File Id="_98" Source="..\bin\release\aircraft\Rascal\Engines\Zenoah_G-26A.xml.new" />
|
||||
</Component>
|
||||
</Directory>
|
||||
<Directory Id="pl54" Name="pl">
|
||||
<Component Id="_comp55" Guid="f8b404d3-6d8b-459b-81ae-5538993f5f93">
|
||||
<File Id="_56" Source="..\bin\release\pl\ArdupilotMegaPlanner.resources.dll" />
|
||||
<Directory Id="Models98" Name="Models">
|
||||
<Component Id="_comp99" Guid="7f01cb3c-7f32-44ba-bbff-1291cef53ea4">
|
||||
<File Id="_100" Source="..\bin\release\aircraft\Rascal\Models\Rascal.rgb" />
|
||||
<File Id="_101" Source="..\bin\release\aircraft\Rascal\Models\Rascal.rgb.new" />
|
||||
<File Id="_102" Source="..\bin\release\aircraft\Rascal\Models\Rascal110-000-013.ac" />
|
||||
<File Id="_103" Source="..\bin\release\aircraft\Rascal\Models\Rascal110-000-013.ac.new" />
|
||||
<File Id="_104" Source="..\bin\release\aircraft\Rascal\Models\Rascal110.xml" />
|
||||
<File Id="_105" Source="..\bin\release\aircraft\Rascal\Models\Rascal110.xml.new" />
|
||||
<File Id="_106" Source="..\bin\release\aircraft\Rascal\Models\smoke.png" />
|
||||
<File Id="_107" Source="..\bin\release\aircraft\Rascal\Models\smoke.png.new" />
|
||||
<File Id="_108" Source="..\bin\release\aircraft\Rascal\Models\smokeW.xml" />
|
||||
<File Id="_109" Source="..\bin\release\aircraft\Rascal\Models\smokeW.xml.new" />
|
||||
<File Id="_110" Source="..\bin\release\aircraft\Rascal\Models\Trajectory-Marker.ac" />
|
||||
<File Id="_111" Source="..\bin\release\aircraft\Rascal\Models\Trajectory-Marker.ac.new" />
|
||||
<File Id="_112" Source="..\bin\release\aircraft\Rascal\Models\Trajectory-Marker.xml" />
|
||||
<File Id="_113" Source="..\bin\release\aircraft\Rascal\Models\Trajectory-Marker.xml.new" />
|
||||
</Component>
|
||||
</Directory>
|
||||
<Directory Id="Resources56" Name="Resources">
|
||||
<Component Id="_comp57" Guid="455d632e-d45a-4d33-8686-48c2e734c6a2">
|
||||
<File Id="_58" Source="..\bin\release\Resources\MAVCmd.txt" />
|
||||
<File Id="_59" Source="..\bin\release\Resources\Welcome_to_Michael_Oborne.rtf" />
|
||||
<Directory Id="Systems113" Name="Systems">
|
||||
<Component Id="_comp114" Guid="c86479fa-e506-4548-9e69-1e25a49d2a80">
|
||||
<File Id="_115" Source="..\bin\release\aircraft\Rascal\Systems\110-autopilot.xml" />
|
||||
<File Id="_116" Source="..\bin\release\aircraft\Rascal\Systems\110-autopilot.xml.new" />
|
||||
<File Id="_117" Source="..\bin\release\aircraft\Rascal\Systems\airdata.nas" />
|
||||
<File Id="_118" Source="..\bin\release\aircraft\Rascal\Systems\airdata.nas.new" />
|
||||
<File Id="_119" Source="..\bin\release\aircraft\Rascal\Systems\electrical.xml" />
|
||||
<File Id="_120" Source="..\bin\release\aircraft\Rascal\Systems\electrical.xml.new" />
|
||||
<File Id="_121" Source="..\bin\release\aircraft\Rascal\Systems\main.nas" />
|
||||
<File Id="_122" Source="..\bin\release\aircraft\Rascal\Systems\main.nas.new" />
|
||||
<File Id="_123" Source="..\bin\release\aircraft\Rascal\Systems\ugear.nas" />
|
||||
</Component>
|
||||
</Directory>
|
||||
<Directory Id="ru_RU59" Name="ru-RU">
|
||||
<Component Id="_comp60" Guid="d8f500bc-350b-4b04-9926-ba6308e4dbb4">
|
||||
<File Id="_61" Source="..\bin\release\ru-RU\ArdupilotMegaPlanner.resources.dll" />
|
||||
</Directory>
|
||||
</Directory>
|
||||
<Directory Id="Driver123" Name="Driver">
|
||||
<Component Id="_comp124" Guid="1ead128f-9773-4e64-85a6-794cc19a761a">
|
||||
<File Id="_125" Source="..\bin\release\Driver\Arduino MEGA 2560.inf" />
|
||||
<File Id="_126" Source="..\bin\release\Driver\Arduino MEGA 2560.inf.new" />
|
||||
</Component>
|
||||
</Directory>
|
||||
<Directory Id="zh_Hans61" Name="zh-Hans">
|
||||
<Component Id="_comp62" Guid="698d99e5-250c-435f-b596-dd99d9c68e64">
|
||||
<File Id="_63" Source="..\bin\release\zh-Hans\ArdupilotMegaPlanner.resources.dll" />
|
||||
<Directory Id="es_ES126" Name="es-ES">
|
||||
<Component Id="_comp127" Guid="804df9a1-a600-479f-90c0-d009f7b28d64">
|
||||
<File Id="_128" Source="..\bin\release\es-ES\ArdupilotMegaPlanner.resources.dll" />
|
||||
</Component>
|
||||
</Directory>
|
||||
<Directory Id="zh_TW63" Name="zh-TW">
|
||||
<Component Id="_comp64" Guid="d051d520-b580-4990-b1ab-12107aa8571f">
|
||||
<File Id="_65" Source="..\bin\release\zh-TW\ArdupilotMegaPlanner.resources.dll" />
|
||||
<Directory Id="fr128" Name="fr">
|
||||
<Component Id="_comp129" Guid="2e5d2e24-cc1b-454a-bd74-ae2db91ceaa5">
|
||||
<File Id="_130" Source="..\bin\release\fr\ArdupilotMegaPlanner.resources.dll" />
|
||||
</Component>
|
||||
</Directory>
|
||||
<Directory Id="it_IT130" Name="it-IT">
|
||||
<Component Id="_comp131" Guid="ed5edb47-dda4-44e2-99b5-a7800c8509ea">
|
||||
<File Id="_132" Source="..\bin\release\it-IT\ArdupilotMegaPlanner.resources.dll" />
|
||||
</Component>
|
||||
</Directory>
|
||||
<Directory Id="jsbsim132" Name="jsbsim">
|
||||
<Component Id="_comp133" Guid="6ad32fa2-5d4f-4aa2-a6b5-c0ab66ec4c4f">
|
||||
<File Id="_134" Source="..\bin\release\jsbsim\fgout.xml" />
|
||||
<File Id="_135" Source="..\bin\release\jsbsim\rascal_test.xml" />
|
||||
</Component>
|
||||
</Directory>
|
||||
<Directory Id="m3u135" Name="m3u">
|
||||
<Component Id="_comp136" Guid="829a6282-d9c2-4ec2-959d-7695ac34c648">
|
||||
<File Id="_137" Source="..\bin\release\m3u\both.m3u" />
|
||||
<File Id="_138" Source="..\bin\release\m3u\hud.m3u" />
|
||||
<File Id="_139" Source="..\bin\release\m3u\map.m3u" />
|
||||
<File Id="_140" Source="..\bin\release\m3u\networklink.kml" />
|
||||
</Component>
|
||||
</Directory>
|
||||
<Directory Id="pl140" Name="pl">
|
||||
<Component Id="_comp141" Guid="640061ad-2bd3-495b-bfa1-6990d087b35a">
|
||||
<File Id="_142" Source="..\bin\release\pl\ArdupilotMegaPlanner.resources.dll" />
|
||||
</Component>
|
||||
</Directory>
|
||||
<Directory Id="Resources142" Name="Resources">
|
||||
<Component Id="_comp143" Guid="60f0d36e-6671-48a3-b87c-2e31a3fc50a5">
|
||||
<File Id="_144" Source="..\bin\release\Resources\MAVCmd.txt" />
|
||||
<File Id="_145" Source="..\bin\release\Resources\MAVCmd.txt.new" />
|
||||
<File Id="_146" Source="..\bin\release\Resources\Welcome_to_Michael_Oborne.rtf" />
|
||||
<File Id="_147" Source="..\bin\release\Resources\Welcome_to_Michael_Oborne.rtf.new" />
|
||||
</Component>
|
||||
</Directory>
|
||||
<Directory Id="ru_RU147" Name="ru-RU">
|
||||
<Component Id="_comp148" Guid="039b8419-4534-43d0-af2f-1418890dd3d6">
|
||||
<File Id="_149" Source="..\bin\release\ru-RU\ArdupilotMegaPlanner.resources.dll" />
|
||||
</Component>
|
||||
</Directory>
|
||||
<Directory Id="zh_Hans149" Name="zh-Hans">
|
||||
<Component Id="_comp150" Guid="287da807-7260-47c2-b782-b376d95ce68e">
|
||||
<File Id="_151" Source="..\bin\release\zh-Hans\ArdupilotMegaPlanner.resources.dll" />
|
||||
</Component>
|
||||
</Directory>
|
||||
<Directory Id="zh_TW151" Name="zh-TW">
|
||||
<Component Id="_comp152" Guid="87db4ac6-634b-4502-a649-ed59566fd6fe">
|
||||
<File Id="_153" Source="..\bin\release\zh-TW\ArdupilotMegaPlanner.resources.dll" />
|
||||
</Component>
|
||||
</Directory>
|
||||
|
||||
|
@ -158,16 +287,27 @@
|
|||
<ComponentRef Id="InstallDirPermissions" />
|
||||
|
||||
<ComponentRef Id="_comp1" />
|
||||
<ComponentRef Id="_comp42" />
|
||||
<ComponentRef Id="_comp44" />
|
||||
<ComponentRef Id="_comp46" />
|
||||
<ComponentRef Id="_comp48" />
|
||||
<ComponentRef Id="_comp50" />
|
||||
<ComponentRef Id="_comp53" />
|
||||
<ComponentRef Id="_comp55" />
|
||||
<ComponentRef Id="_comp57" />
|
||||
<ComponentRef Id="_comp60" />
|
||||
<ComponentRef Id="_comp62" />
|
||||
<ComponentRef Id="_comp64" />
|
||||
<ComponentRef Id="_comp68" />
|
||||
<ComponentRef Id="_comp71" />
|
||||
<ComponentRef Id="_comp81" />
|
||||
<ComponentRef Id="_comp91" />
|
||||
<ComponentRef Id="_comp94" />
|
||||
<ComponentRef Id="_comp99" />
|
||||
<ComponentRef Id="_comp114" />
|
||||
<ComponentRef Id="_comp124" />
|
||||
<ComponentRef Id="_comp127" />
|
||||
<ComponentRef Id="_comp129" />
|
||||
<ComponentRef Id="_comp131" />
|
||||
<ComponentRef Id="_comp133" />
|
||||
<ComponentRef Id="_comp136" />
|
||||
<ComponentRef Id="_comp141" />
|
||||
<ComponentRef Id="_comp143" />
|
||||
<ComponentRef Id="_comp148" />
|
||||
<ComponentRef Id="_comp150" />
|
||||
<ComponentRef Id="_comp152" />
|
||||
|
||||
|
||||
<ComponentRef Id="ApplicationShortcut" />
|
||||
|
@ -188,7 +328,7 @@
|
|||
<Property Id="WIXUI_EXITDIALOGOPTIONALCHECKBOXTEXT" Value="Launch APM Planner" />
|
||||
|
||||
<!-- Step 3: Include the custom action -->
|
||||
<Property Id="WixShellExecTarget" Value="[#_5]" />
|
||||
<Property Id="WixShellExecTarget" Value="[#_7]" />
|
||||
<CustomAction Id="LaunchApplication"
|
||||
BinaryKey="WixCA"
|
||||
DllEntry="WixShellExec"
|
||||
|
|
Binary file not shown.
|
@ -33,6 +33,6 @@ using System.Resources;
|
|||
// You can specify all the values or you can default the Build and Revision Numbers
|
||||
// by using the '*' as shown below:
|
||||
// [assembly: AssemblyVersion("1.0.*")]
|
||||
[assembly: AssemblyVersion("1.0.0.0")]
|
||||
[assembly: AssemblyFileVersion("1.1.62")]
|
||||
[assembly: AssemblyVersion("1.1.*")]
|
||||
[assembly: AssemblyFileVersion("1.1.63")]
|
||||
[assembly: NeutralResourcesLanguageAttribute("")]
|
||||
|
|
Binary file not shown.
|
@ -0,0 +1 @@
|
|||
Hi
|
|
@ -0,0 +1 @@
|
|||
1.1.4482.15190
|
|
@ -116,7 +116,7 @@ namespace wix
|
|||
{
|
||||
string newid = System.Guid.NewGuid().ToString();
|
||||
|
||||
newid = "{625389D7-EB3C-4d77-A5F6-A285CF99437D}";
|
||||
newid = "*";
|
||||
|
||||
StreamReader sr = new StreamReader(File.OpenRead("../Properties/AssemblyInfo.cs"));
|
||||
|
||||
|
@ -138,10 +138,18 @@ namespace wix
|
|||
|
||||
|
||||
<Product Id=""" + newid + @""" Name=""APM Planner"" Language=""1033"" Version="""+version+@""" Manufacturer=""Michael Oborne"" UpgradeCode=""{625389D7-EB3C-4d77-A5F6-A285CF99437D}"">
|
||||
|
||||
<Package Description=""APM Planner Installer"" Comments=""Apm Planner Installer"" Manufacturer=""Michael Oborne"" InstallerVersion=""200"" Compressed=""yes"" />
|
||||
|
||||
<MajorUpgrade DowngradeErrorMessage=""A later version of [ProductName] is already installed. Setup will now exit.""/>
|
||||
|
||||
<Upgrade Id=""{625389D7-EB3C-4d77-A5F6-A285CF99437D}"">
|
||||
<UpgradeVersion OnlyDetect=""yes"" Minimum=""" + version + @""" Property=""NEWERVERSIONDETECTED"" IncludeMinimum=""no"" />
|
||||
<UpgradeVersion OnlyDetect=""no"" Maximum=""" + version + @""" Property=""OLDERVERSIONBEINGUPGRADED"" IncludeMaximum=""no"" />
|
||||
</Upgrade>
|
||||
|
||||
<InstallExecuteSequence>
|
||||
<RemoveExistingProducts After=""InstallInitialize"" />
|
||||
</InstallExecuteSequence>
|
||||
|
||||
<PropertyRef Id=""NETFRAMEWORK35"" />
|
||||
|
||||
|
@ -251,7 +259,7 @@ data = @"
|
|||
|
||||
foreach (string filepath in files)
|
||||
{
|
||||
if (filepath.EndsWith("config.xml") || filepath.Contains("ArdupilotPlanner.log"))
|
||||
if (filepath.ToLower().EndsWith("release\\config.xml") || filepath.ToLower().Contains("ardupilotplanner.log") || filepath.ToLower().Contains("dataflash.bin") || filepath.ToLower().Contains(".etag"))
|
||||
continue;
|
||||
no++;
|
||||
sw.WriteLine("<File Id=\"_" + no + "\" Source=\"" + filepath + "\" />");
|
||||
|
|
Loading…
Reference in New Issue