mirror of https://github.com/ArduPilot/ardupilot
parent
dd9065123c
commit
49a097a8f1
|
@ -124,7 +124,7 @@ namespace ArdupilotMega.Antenna
|
|||
|
||||
byte target = (byte)((((PointAtAngle / range ) * 2) * 127 + 127) * _tiltreverse);
|
||||
|
||||
Console.WriteLine("T " + Angle + " " + target + " " + PointAtAngle);
|
||||
//Console.WriteLine("T " + Angle + " " + target + " " + PointAtAngle);
|
||||
|
||||
var buffer = new byte[] { 0xff, TiltAddress, target };
|
||||
ComPort.Write(buffer, 0, buffer.Length);
|
||||
|
@ -142,7 +142,11 @@ namespace ArdupilotMega.Antenna
|
|||
|
||||
public bool Close()
|
||||
{
|
||||
ComPort.Close();
|
||||
try
|
||||
{
|
||||
ComPort.Close();
|
||||
}
|
||||
catch { }
|
||||
return true;
|
||||
}
|
||||
|
||||
|
|
|
@ -51,7 +51,7 @@
|
|||
<CheckForOverflowUnderflow>false</CheckForOverflowUnderflow>
|
||||
<NoStdLib>false</NoStdLib>
|
||||
<UseVSHostingProcess>true</UseVSHostingProcess>
|
||||
<FileAlignment>1024</FileAlignment>
|
||||
<FileAlignment>512</FileAlignment>
|
||||
</PropertyGroup>
|
||||
<PropertyGroup Condition=" '$(Configuration)|$(Platform)' == 'Release|x86' ">
|
||||
<PlatformTarget>x86</PlatformTarget>
|
||||
|
@ -68,7 +68,7 @@
|
|||
<DebugSymbols>true</DebugSymbols>
|
||||
<NoStdLib>false</NoStdLib>
|
||||
<UseVSHostingProcess>true</UseVSHostingProcess>
|
||||
<FileAlignment>1024</FileAlignment>
|
||||
<FileAlignment>512</FileAlignment>
|
||||
</PropertyGroup>
|
||||
<PropertyGroup>
|
||||
<StartupObject>ArdupilotMega.Program</StartupObject>
|
||||
|
|
|
@ -42,6 +42,7 @@ namespace ArdupilotMega.Controls
|
|||
|
||||
private void RunBackgroundOperation(object o)
|
||||
{
|
||||
Thread.CurrentThread.Name = "ProgressReporterDialogue Background thread";
|
||||
try
|
||||
{
|
||||
if (this.DoWork != null) this.DoWork(this, doWorkArgs);
|
||||
|
|
|
@ -275,6 +275,7 @@ namespace ArdupilotMega.GCSViews
|
|||
comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.MAV_DATA_STREAM_POSITION, MainV2.cs.rateposition); // request gps
|
||||
comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.MAV_DATA_STREAM_EXTRA1, MainV2.cs.rateattitude); // request attitude
|
||||
comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.MAV_DATA_STREAM_EXTRA2, MainV2.cs.rateattitude); // request vfr
|
||||
comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.MAV_DATA_STREAM_EXTRA3, MainV2.cs.ratesensors); // request extra stuff - tridge
|
||||
comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.MAV_DATA_STREAM_RAW_SENSORS, MainV2.cs.ratesensors); // request raw sensor
|
||||
comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.MAV_DATA_STREAM_RC_CHANNELS, MainV2.cs.raterc); // request rc info
|
||||
}
|
||||
|
|
|
@ -46,6 +46,8 @@ namespace hud
|
|||
|
||||
bool started = false;
|
||||
|
||||
public bool SixteenXNine = false;
|
||||
|
||||
public HUD()
|
||||
{
|
||||
if (this.DesignMode)
|
||||
|
@ -1552,7 +1554,18 @@ namespace hud
|
|||
{
|
||||
if (DesignMode || !started)
|
||||
return;
|
||||
this.Height = (int)(this.Width / 1.333f);
|
||||
|
||||
|
||||
if (SixteenXNine)
|
||||
{
|
||||
this.Height = (int)(this.Width / 1.777f);
|
||||
}
|
||||
else
|
||||
{
|
||||
// 4x3
|
||||
this.Height = (int)(this.Width / 1.333f);
|
||||
}
|
||||
|
||||
base.OnResize(e);
|
||||
|
||||
graphicsObjectGDIP = Graphics.FromImage(objBitmap);
|
||||
|
|
|
@ -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.45")]
|
||||
[assembly: AssemblyFileVersion("1.1.46")]
|
||||
[assembly: NeutralResourcesLanguageAttribute("")]
|
||||
|
|
Binary file not shown.
Loading…
Reference in New Issue