diff --git a/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj b/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj
index 31a032782f..a465ce3663 100644
--- a/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj
+++ b/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj
@@ -148,11 +148,11 @@
False
- False
+ True
False
- False
+ True
@@ -1147,8 +1147,7 @@
-
-
+ "$(TargetDir)version.exe" "$(TargetPath)" > "$(TargetDir)version.txt"
diff --git a/Tools/ArdupilotMegaPlanner/CodeGen.cs b/Tools/ArdupilotMegaPlanner/CodeGen.cs
index 199bb33324..cdde571ed0 100644
--- a/Tools/ArdupilotMegaPlanner/CodeGen.cs
+++ b/Tools/ArdupilotMegaPlanner/CodeGen.cs
@@ -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);
diff --git a/Tools/ArdupilotMegaPlanner/Controls/CustomMessageBox.cs b/Tools/ArdupilotMegaPlanner/Controls/CustomMessageBox.cs
index 71b2f5f0d2..08863d1bd0 100644
--- a/Tools/ArdupilotMegaPlanner/Controls/CustomMessageBox.cs
+++ b/Tools/ArdupilotMegaPlanner/Controls/CustomMessageBox.cs
@@ -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;
diff --git a/Tools/ArdupilotMegaPlanner/CurrentState.cs b/Tools/ArdupilotMegaPlanner/CurrentState.cs
index 859fc0f1ab..087c85741d 100644
--- a/Tools/ArdupilotMegaPlanner/CurrentState.cs
+++ b/Tools/ArdupilotMegaPlanner/CurrentState.cs
@@ -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;
}
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.resx b/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.resx
index 2157889864..fcbfad4a2a 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.resx
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/FlightData.resx
@@ -910,16 +910,16 @@
NoControl
- 51, 32
+ 29, 32
- 80, 23
+ 127, 23
76
- Log > KML
+ Tlog > Kml or Graph
BUT_log2kml
diff --git a/Tools/ArdupilotMegaPlanner/MAVLink.cs b/Tools/ArdupilotMegaPlanner/MAVLink.cs
index fc6ea283ab..f608a218e5 100644
--- a/Tools/ArdupilotMegaPlanner/MAVLink.cs
+++ b/Tools/ArdupilotMegaPlanner/MAVLink.cs
@@ -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();
}
}
diff --git a/Tools/ArdupilotMegaPlanner/MAVLinkTypes.cs b/Tools/ArdupilotMegaPlanner/MAVLinkTypes.cs
index d1e2fffbfb..ae36010847 100644
--- a/Tools/ArdupilotMegaPlanner/MAVLinkTypes.cs
+++ b/Tools/ArdupilotMegaPlanner/MAVLinkTypes.cs
@@ -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
{
/// 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|
- WAYPOINT=16,
+ NAV_WAYPOINT=16,
/// 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|
- LOITER_UNLIM=17,
+ NAV_LOITER_UNLIM=17,
/// 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|
- LOITER_TURNS=18,
+ NAV_LOITER_TURNS=18,
/// 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|
- LOITER_TIME=19,
+ NAV_LOITER_TIME=19,
/// Return to launch location |Empty| Empty| Empty| Empty| Empty| Empty| Empty|
- RETURN_TO_LAUNCH=20,
+ NAV_RETURN_TO_LAUNCH=20,
/// Land at location |Empty| Empty| Empty| Desired yaw angle.| Latitude| Longitude| Altitude|
- LAND=21,
+ NAV_LAND=21,
/// 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|
- TAKEOFF=22,
+ NAV_TAKEOFF=22,
/// 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|
- ROI=80,
+ NAV_ROI=80,
/// 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|
- PATHPLANNING=81,
+ NAV_PATHPLANNING=81,
/// 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|
- LAST=95,
+ NAV_LAST=95,
/// Delay mission state machine. |Delay in seconds (decimal)| Empty| Empty| Empty| Empty| Empty| Empty|
CONDITION_DELAY=112,
/// Ascend/descend at rate. Delay mission state machine until desired altitude reached. |Descent / Ascend rate (m/s)| Empty| Empty| Empty| Empty| Empty| Finish Altitude|
@@ -915,16 +915,18 @@ namespace ArdupilotMega
{
/// receive errors
public UInt16 rxerrors;
- /// serial errors
- public UInt16 serrors;
/// count of error corrected packets
- public UInt16 fixedp;
+ public UInt16 fixed;
/// local signal strength
public byte rssi;
/// remote signal strength
public byte remrssi;
/// how full the tx buffer is as a percentage
public byte txbuf;
+ /// background noise level
+ public byte noise;
+ /// remote background noise level
+ public byte remnoise;
};
@@ -1108,7 +1110,7 @@ namespace ArdupilotMega
public UInt16 param_index;
/// Onboard parameter id
[MarshalAs(UnmanagedType.ByValArray,SizeConst=16)]
- public byte[] param_id;
+ public string param_id;
/// Onboard parameter type: see MAV_VAR enum
public byte param_type;
@@ -1127,7 +1129,7 @@ namespace ArdupilotMega
public byte target_component;
/// Onboard parameter id
[MarshalAs(UnmanagedType.ByValArray,SizeConst=16)]
- public byte[] param_id;
+ public string param_id;
/// Onboard parameter type: see MAV_VAR enum
public byte param_type;
@@ -2370,5 +2372,5 @@ namespace ArdupilotMega
};
}
- #endif
+#endif
}
diff --git a/Tools/ArdupilotMegaPlanner/MAVLinkTypes0.9.cs b/Tools/ArdupilotMegaPlanner/MAVLinkTypes0.9.cs
index 597333e768..bd6d1276cc 100644
--- a/Tools/ArdupilotMegaPlanner/MAVLinkTypes0.9.cs
+++ b/Tools/ArdupilotMegaPlanner/MAVLinkTypes0.9.cs
@@ -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;
/// how full the tx buffer is as a percentage
public byte txbuf;
+ /// background noise level
+ public byte noise;
+ /// remote background noise level
+ public byte remnoise;
/// receive errors
public UInt16 rxerrors;
- /// serial errors
- public UInt16 serrors;
/// count of error corrected packets
public UInt16 fixedp;
@@ -1830,5 +1832,5 @@ namespace ArdupilotMega
};
}
- #endif
+#endif
}
diff --git a/Tools/ArdupilotMegaPlanner/MainV2.cs b/Tools/ArdupilotMegaPlanner/MainV2.cs
index 62a16e89d4..5ec4ebab68 100644
--- a/Tools/ArdupilotMegaPlanner/MainV2.cs
+++ b/Tools/ArdupilotMegaPlanner/MainV2.cs
@@ -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
diff --git a/Tools/ArdupilotMegaPlanner/Mavlink/MavlinkOther.cs b/Tools/ArdupilotMegaPlanner/Mavlink/MavlinkOther.cs
new file mode 100644
index 0000000000..f01d258e0a
--- /dev/null
+++ b/Tools/ArdupilotMegaPlanner/Mavlink/MavlinkOther.cs
@@ -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
+ }
+}
diff --git a/Tools/ArdupilotMegaPlanner/MavlinkLog.cs b/Tools/ArdupilotMegaPlanner/MavlinkLog.cs
index 707f84ff7c..2f1a7a8c8f 100644
--- a/Tools/ArdupilotMegaPlanner/MavlinkLog.cs
+++ b/Tools/ArdupilotMegaPlanner/MavlinkLog.cs
@@ -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 options)
{
string field = "mag_field Custom";
@@ -913,6 +951,72 @@ namespace ArdupilotMega
}
}
+ void addDistHome(ref List 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);
diff --git a/Tools/ArdupilotMegaPlanner/Msi/installer.bat b/Tools/ArdupilotMegaPlanner/Msi/installer.bat
index 64a7b4d57c..a24e75791b 100644
--- a/Tools/ArdupilotMegaPlanner/Msi/installer.bat
+++ b/Tools/ArdupilotMegaPlanner/Msi/installer.bat
@@ -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
diff --git a/Tools/ArdupilotMegaPlanner/Msi/installer.wxs b/Tools/ArdupilotMegaPlanner/Msi/installer.wxs
index 7d03a402f9..b30f164d29 100644
--- a/Tools/ArdupilotMegaPlanner/Msi/installer.wxs
+++ b/Tools/ArdupilotMegaPlanner/Msi/installer.wxs
@@ -2,11 +2,19 @@
-
+
+
-
+
+
+
+
+
+
+
+
@@ -23,100 +31,221 @@
-
+
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
-
-
-
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
-
-
-
+
+
+
+
-
-
-
+
+
+
+
+
+
+
+
+
+
+
-
-
-
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
-
-
-
-
-
-
+
+
+
+
+
+
-
-
-
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
-
-
-
-
+
+
+
+
+
+
+
+
+
+
+
-
-
-
+
+
+
+
+
+
-
-
-
+
+
+
-
-
-
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
@@ -158,16 +287,27 @@
-
-
-
-
-
+
-
-
-
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
@@ -188,7 +328,7 @@
-
+
+
-
+
+
+
+
+
+
+
+
@@ -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("");