mirror of https://github.com/ArduPilot/ardupilot
parent
cae10dc8f6
commit
0f7b317a8d
|
@ -285,24 +285,21 @@ namespace ArdupilotMega
|
||||||
mode = "Acro";
|
mode = "Acro";
|
||||||
break;
|
break;
|
||||||
case (byte)102:
|
case (byte)102:
|
||||||
mode = "Simple";
|
|
||||||
break;
|
|
||||||
case (byte)103:
|
|
||||||
mode = "Alt Hold";
|
mode = "Alt Hold";
|
||||||
break;
|
break;
|
||||||
case (byte)104:
|
case (byte)103:
|
||||||
mode = "Auto";
|
mode = "Auto";
|
||||||
break;
|
break;
|
||||||
case (byte)105:
|
case (byte)104:
|
||||||
mode = "Guided";
|
mode = "Guided";
|
||||||
break;
|
break;
|
||||||
case (byte)106:
|
case (byte)105:
|
||||||
mode = "Loiter";
|
mode = "Loiter";
|
||||||
break;
|
break;
|
||||||
case (byte)107:
|
case (byte)106:
|
||||||
mode = "RTL";
|
mode = "RTL";
|
||||||
break;
|
break;
|
||||||
case (byte)108:
|
case (byte)107:
|
||||||
mode = "Circle";
|
mode = "Circle";
|
||||||
break;
|
break;
|
||||||
case (byte)ArdupilotMega.MAVLink.MAV_MODE.MAV_MODE_MANUAL:
|
case (byte)ArdupilotMega.MAVLink.MAV_MODE.MAV_MODE_MANUAL:
|
||||||
|
@ -546,6 +543,27 @@ namespace ArdupilotMega
|
||||||
//MAVLink.packets[MAVLink.MAVLINK_MSG_ID_RAW_IMU] = null;
|
//MAVLink.packets[MAVLink.MAVLINK_MSG_ID_RAW_IMU] = null;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
if (MAVLink.packets[MAVLink.MAVLINK_MSG_ID_SCALED_IMU] != null)
|
||||||
|
{
|
||||||
|
var imu = new MAVLink.__mavlink_scaled_imu_t();
|
||||||
|
|
||||||
|
object temp = imu;
|
||||||
|
|
||||||
|
MAVLink.ByteArrayToStructure(MAVLink.packets[MAVLink.MAVLINK_MSG_ID_SCALED_IMU], ref temp, 6);
|
||||||
|
|
||||||
|
imu = (MAVLink.__mavlink_scaled_imu_t)(temp);
|
||||||
|
|
||||||
|
gx = imu.xgyro;
|
||||||
|
gy = imu.ygyro;
|
||||||
|
gz = imu.zgyro;
|
||||||
|
|
||||||
|
ax = imu.xacc;
|
||||||
|
ay = imu.yacc;
|
||||||
|
az = imu.zacc;
|
||||||
|
|
||||||
|
//MAVLink.packets[MAVLink.MAVLINK_MSG_ID_RAW_IMU] = null;
|
||||||
|
}
|
||||||
|
|
||||||
if (MAVLink.packets[MAVLink.MAVLINK_MSG_ID_VFR_HUD] != null)
|
if (MAVLink.packets[MAVLink.MAVLINK_MSG_ID_VFR_HUD] != null)
|
||||||
{
|
{
|
||||||
MAVLink.__mavlink_vfr_hud_t vfr = new MAVLink.__mavlink_vfr_hud_t();
|
MAVLink.__mavlink_vfr_hud_t vfr = new MAVLink.__mavlink_vfr_hud_t();
|
||||||
|
|
|
@ -1066,7 +1066,7 @@ System.ComponentModel.Category("Values")]
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
greenPen.Width = 4;
|
||||||
|
|
||||||
// vsi
|
// vsi
|
||||||
|
|
||||||
|
|
|
@ -210,6 +210,7 @@ namespace ArdupilotMega
|
||||||
|
|
||||||
Console.WriteLine("Done open " + sysid + " " + compid);
|
Console.WriteLine("Done open " + sysid + " " + compid);
|
||||||
|
|
||||||
|
packetslost = 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
public static byte[] StructureToByteArrayEndian(params object[] list)
|
public static byte[] StructureToByteArrayEndian(params object[] list)
|
||||||
|
@ -1491,6 +1492,7 @@ namespace ArdupilotMega
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
|
MainV2.cs.datetime = DateTime.Now;
|
||||||
temp[count] = (byte)BaseStream.ReadByte();
|
temp[count] = (byte)BaseStream.ReadByte();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -1565,6 +1567,15 @@ namespace ArdupilotMega
|
||||||
|
|
||||||
Array.Resize<byte>(ref temp, count);
|
Array.Resize<byte>(ref temp, count);
|
||||||
|
|
||||||
|
if (packetlosttimer.AddSeconds(10) < DateTime.Now)
|
||||||
|
{
|
||||||
|
packetlosttimer = DateTime.Now;
|
||||||
|
packetslost = (int)(packetslost * 0.8f);
|
||||||
|
packetsnotlost = (int)(packetsnotlost * 0.8f);
|
||||||
|
}
|
||||||
|
|
||||||
|
MainV2.cs.linkqualitygcs = (ushort)((packetsnotlost / (packetsnotlost + packetslost)) * 100);
|
||||||
|
|
||||||
if (bpstime.Second != DateTime.Now.Second && !logreadmode)
|
if (bpstime.Second != DateTime.Now.Second && !logreadmode)
|
||||||
{
|
{
|
||||||
Console.WriteLine("bps {0} loss {1} left {2}", bps1, synclost, BaseStream.BytesToRead);
|
Console.WriteLine("bps {0} loss {1} left {2}", bps1, synclost, BaseStream.BytesToRead);
|
||||||
|
@ -1602,6 +1613,7 @@ namespace ArdupilotMega
|
||||||
|
|
||||||
try
|
try
|
||||||
{
|
{
|
||||||
|
|
||||||
if ((temp[0] == 'U' || temp[0] == 254) && temp.Length >= temp[1])
|
if ((temp[0] == 'U' || temp[0] == 254) && temp.Length >= temp[1])
|
||||||
{
|
{
|
||||||
if (temp[2] != ((recvpacketcount + 1) % 0x100))
|
if (temp[2] != ((recvpacketcount + 1) % 0x100))
|
||||||
|
@ -1620,15 +1632,6 @@ namespace ArdupilotMega
|
||||||
Console.WriteLine("lost {0} pkts {1}", temp[2], (int)packetslost);
|
Console.WriteLine("lost {0} pkts {1}", temp[2], (int)packetslost);
|
||||||
}
|
}
|
||||||
|
|
||||||
if (packetlosttimer.AddSeconds(10) < DateTime.Now)
|
|
||||||
{
|
|
||||||
packetlosttimer = DateTime.Now;
|
|
||||||
packetslost = (int)(packetslost *0.8f);
|
|
||||||
packetsnotlost = (int)(packetsnotlost *0.8f);
|
|
||||||
}
|
|
||||||
|
|
||||||
MainV2.cs.linkqualitygcs = (ushort)((packetsnotlost / (packetsnotlost + packetslost)) * 100);
|
|
||||||
|
|
||||||
packetsnotlost++;
|
packetsnotlost++;
|
||||||
|
|
||||||
recvpacketcount = temp[2];
|
recvpacketcount = temp[2];
|
||||||
|
|
|
@ -884,6 +884,8 @@ namespace ArdupilotMega
|
||||||
|
|
||||||
DateTime speechcustomtime = DateTime.Now;
|
DateTime speechcustomtime = DateTime.Now;
|
||||||
|
|
||||||
|
DateTime linkqualitytime = DateTime.Now;
|
||||||
|
|
||||||
while (serialthread)
|
while (serialthread)
|
||||||
{
|
{
|
||||||
try
|
try
|
||||||
|
@ -936,6 +938,21 @@ namespace ArdupilotMega
|
||||||
speechcustomtime = DateTime.Now;
|
speechcustomtime = DateTime.Now;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
if ((DateTime.Now - comPort.lastvalidpacket).TotalSeconds > 10)
|
||||||
|
{
|
||||||
|
MainV2.cs.linkqualitygcs = 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
if ((DateTime.Now - comPort.lastvalidpacket).TotalSeconds >= 1)
|
||||||
|
{
|
||||||
|
GCSViews.FlightData.myhud.Invalidate();
|
||||||
|
if (linkqualitytime.Second != DateTime.Now.Second)
|
||||||
|
{
|
||||||
|
MainV2.cs.linkqualitygcs = (ushort)(MainV2.cs.linkqualitygcs * 0.8f);
|
||||||
|
linkqualitytime = DateTime.Now;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
if (speechenable && talk != null && (MainV2.comPort.logreadmode || comPort.BaseStream.IsOpen))
|
if (speechenable && talk != null && (MainV2.comPort.logreadmode || comPort.BaseStream.IsOpen))
|
||||||
{
|
{
|
||||||
float warnalt = float.MaxValue;
|
float warnalt = float.MaxValue;
|
||||||
|
@ -975,7 +992,6 @@ namespace ArdupilotMega
|
||||||
if (MainV2.talk.State == SynthesizerState.Ready)
|
if (MainV2.talk.State == SynthesizerState.Ready)
|
||||||
MainV2.talk.SpeakAsync("WARNING No Data for " + (int)(DateTime.Now - comPort.lastvalidpacket).TotalSeconds + " Seconds");
|
MainV2.talk.SpeakAsync("WARNING No Data for " + (int)(DateTime.Now - comPort.lastvalidpacket).TotalSeconds + " Seconds");
|
||||||
}
|
}
|
||||||
MainV2.cs.linkqualitygcs = 0;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
//Console.WriteLine(comPort.BaseStream.BytesToRead);
|
//Console.WriteLine(comPort.BaseStream.BytesToRead);
|
||||||
|
@ -1479,6 +1495,12 @@ namespace ArdupilotMega
|
||||||
MainV2.comPort.Open(false);
|
MainV2.comPort.Open(false);
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
if (keyData == (Keys.Control | Keys.Y)) // for ryan beall
|
||||||
|
{
|
||||||
|
MainV2.comPort.doAction(MAVLink.MAV_ACTION.MAV_ACTION_STORAGE_WRITE);
|
||||||
|
MessageBox.Show("Done MAV_ACTION_STORAGE_WRITE");
|
||||||
|
return true;
|
||||||
|
}
|
||||||
if (keyData == (Keys.Control | Keys.J)) // for jani
|
if (keyData == (Keys.Control | Keys.J)) // for jani
|
||||||
{
|
{
|
||||||
string data = "!!";
|
string data = "!!";
|
||||||
|
|
|
@ -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.0.69")]
|
[assembly: AssemblyFileVersion("1.0.70")]
|
||||||
[assembly: NeutralResourcesLanguageAttribute("")]
|
[assembly: NeutralResourcesLanguageAttribute("")]
|
||||||
|
|
Loading…
Reference in New Issue