mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
APM Planner 1.1.46
update to request extra3 stream.
This commit is contained in:
parent
73dafe537e
commit
c2fa44d24e
@ -124,7 +124,7 @@ namespace ArdupilotMega.Antenna
|
|||||||
|
|
||||||
byte target = (byte)((((PointAtAngle / range ) * 2) * 127 + 127) * _tiltreverse);
|
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 };
|
var buffer = new byte[] { 0xff, TiltAddress, target };
|
||||||
ComPort.Write(buffer, 0, buffer.Length);
|
ComPort.Write(buffer, 0, buffer.Length);
|
||||||
@ -142,7 +142,11 @@ namespace ArdupilotMega.Antenna
|
|||||||
|
|
||||||
public bool Close()
|
public bool Close()
|
||||||
{
|
{
|
||||||
ComPort.Close();
|
try
|
||||||
|
{
|
||||||
|
ComPort.Close();
|
||||||
|
}
|
||||||
|
catch { }
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -51,7 +51,7 @@
|
|||||||
<CheckForOverflowUnderflow>false</CheckForOverflowUnderflow>
|
<CheckForOverflowUnderflow>false</CheckForOverflowUnderflow>
|
||||||
<NoStdLib>false</NoStdLib>
|
<NoStdLib>false</NoStdLib>
|
||||||
<UseVSHostingProcess>true</UseVSHostingProcess>
|
<UseVSHostingProcess>true</UseVSHostingProcess>
|
||||||
<FileAlignment>1024</FileAlignment>
|
<FileAlignment>512</FileAlignment>
|
||||||
</PropertyGroup>
|
</PropertyGroup>
|
||||||
<PropertyGroup Condition=" '$(Configuration)|$(Platform)' == 'Release|x86' ">
|
<PropertyGroup Condition=" '$(Configuration)|$(Platform)' == 'Release|x86' ">
|
||||||
<PlatformTarget>x86</PlatformTarget>
|
<PlatformTarget>x86</PlatformTarget>
|
||||||
@ -68,7 +68,7 @@
|
|||||||
<DebugSymbols>true</DebugSymbols>
|
<DebugSymbols>true</DebugSymbols>
|
||||||
<NoStdLib>false</NoStdLib>
|
<NoStdLib>false</NoStdLib>
|
||||||
<UseVSHostingProcess>true</UseVSHostingProcess>
|
<UseVSHostingProcess>true</UseVSHostingProcess>
|
||||||
<FileAlignment>1024</FileAlignment>
|
<FileAlignment>512</FileAlignment>
|
||||||
</PropertyGroup>
|
</PropertyGroup>
|
||||||
<PropertyGroup>
|
<PropertyGroup>
|
||||||
<StartupObject>ArdupilotMega.Program</StartupObject>
|
<StartupObject>ArdupilotMega.Program</StartupObject>
|
||||||
|
@ -42,6 +42,7 @@ namespace ArdupilotMega.Controls
|
|||||||
|
|
||||||
private void RunBackgroundOperation(object o)
|
private void RunBackgroundOperation(object o)
|
||||||
{
|
{
|
||||||
|
Thread.CurrentThread.Name = "ProgressReporterDialogue Background thread";
|
||||||
try
|
try
|
||||||
{
|
{
|
||||||
if (this.DoWork != null) this.DoWork(this, doWorkArgs);
|
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_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_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_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_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
|
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;
|
bool started = false;
|
||||||
|
|
||||||
|
public bool SixteenXNine = false;
|
||||||
|
|
||||||
public HUD()
|
public HUD()
|
||||||
{
|
{
|
||||||
if (this.DesignMode)
|
if (this.DesignMode)
|
||||||
@ -1552,7 +1554,18 @@ namespace hud
|
|||||||
{
|
{
|
||||||
if (DesignMode || !started)
|
if (DesignMode || !started)
|
||||||
return;
|
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);
|
base.OnResize(e);
|
||||||
|
|
||||||
graphicsObjectGDIP = Graphics.FromImage(objBitmap);
|
graphicsObjectGDIP = Graphics.FromImage(objBitmap);
|
||||||
|
@ -34,5 +34,5 @@ using System.Resources;
|
|||||||
// by using the '*' as shown below:
|
// by using the '*' as shown below:
|
||||||
// [assembly: AssemblyVersion("1.0.*")]
|
// [assembly: AssemblyVersion("1.0.*")]
|
||||||
[assembly: AssemblyVersion("1.0.0.0")]
|
[assembly: AssemblyVersion("1.0.0.0")]
|
||||||
[assembly: AssemblyFileVersion("1.1.45")]
|
[assembly: AssemblyFileVersion("1.1.46")]
|
||||||
[assembly: NeutralResourcesLanguageAttribute("")]
|
[assembly: NeutralResourcesLanguageAttribute("")]
|
||||||
|
Binary file not shown.
Loading…
Reference in New Issue
Block a user