From b72719cc77629889d24a9bd9d5555a8c562a4ba3 Mon Sep 17 00:00:00 2001 From: Michael Oborne Date: Fri, 20 Jan 2012 15:36:01 +0800 Subject: [PATCH] APM Planner 1.1.24 change verify alt action fix hil throttle scaling Thanks Justin --- Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.cs | 11 +++++++++-- Tools/ArdupilotMegaPlanner/GCSViews/Simulation.cs | 2 +- Tools/ArdupilotMegaPlanner/Properties/AssemblyInfo.cs | 2 +- 3 files changed, 11 insertions(+), 4 deletions(-) diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.cs b/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.cs index aa129168c1..82526a1e9c 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.cs @@ -298,7 +298,14 @@ namespace ArdupilotMega.GCSViews // online verify height if (isonline && CHK_geheight.Checked) { - cell.Value = ((int)getGEAlt(lat, lng) + int.Parse(TXT_DefaultAlt.Text)).ToString(); + if (CHK_altmode.Checked) + { + cell.Value = ((int)getGEAlt(lat, lng) + int.Parse(TXT_DefaultAlt.Text)).ToString(); + } + else + { + cell.Value = ((int)getGEAlt(lat, lng) + int.Parse(TXT_DefaultAlt.Text) - float.Parse(TXT_homealt.Text)).ToString(); + } } else { @@ -2970,7 +2977,7 @@ namespace ArdupilotMega.GCSViews if (MainV2.cs.firmware == MainV2.Firmwares.ArduPlane) { - routes.Markers.Add(new GMapMarkerPlane(currentloc, MainV2.cs.yaw, MainV2.cs.groundcourse, MainV2.cs.nav_bearing, MainV2.cs.target_bearing)); + routes.Markers.Add(new GMapMarkerPlane(currentloc, MainV2.cs.yaw, MainV2.cs.groundcourse, MainV2.cs.nav_bearing, MainV2.cs.target_bearing) { ToolTipText = MainV2.cs.alt.ToString("0"), ToolTipMode = MarkerTooltipMode.Always }); } else { diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/Simulation.cs b/Tools/ArdupilotMegaPlanner/GCSViews/Simulation.cs index f6bded10da..12701c737d 100644 --- a/Tools/ArdupilotMegaPlanner/GCSViews/Simulation.cs +++ b/Tools/ArdupilotMegaPlanner/GCSViews/Simulation.cs @@ -1328,7 +1328,7 @@ namespace ArdupilotMega.GCSViews roll_out = (float)MainV2.cs.hilch1 / rollgain; pitch_out = (float)MainV2.cs.hilch2 / pitchgain; - throttle_out = ((float)MainV2.cs.hilch3 + 5000) / throttlegain; + throttle_out = ((float)MainV2.cs.hilch3 / 2 + 5000) / throttlegain; rudder_out = (float)MainV2.cs.hilch4 / ruddergain; } diff --git a/Tools/ArdupilotMegaPlanner/Properties/AssemblyInfo.cs b/Tools/ArdupilotMegaPlanner/Properties/AssemblyInfo.cs index d0371afd9f..644567d505 100644 --- a/Tools/ArdupilotMegaPlanner/Properties/AssemblyInfo.cs +++ b/Tools/ArdupilotMegaPlanner/Properties/AssemblyInfo.cs @@ -34,5 +34,5 @@ using System.Resources; // by using the '*' as shown below: // [assembly: AssemblyVersion("1.0.*")] [assembly: AssemblyVersion("1.0.0.0")] -[assembly: AssemblyFileVersion("1.1.23")] +[assembly: AssemblyFileVersion("1.1.24")] [assembly: NeutralResourcesLanguageAttribute("")]