Mission Planner 1.2.7
add wind from ap add wp every x m in grid mode fix hil problem fix control-s update mavlink format
This commit is contained in:
parent
93f918f3e0
commit
fcdc9b28f6
@ -182,10 +182,6 @@
|
||||
<Reference Include="OpenTK.GLControl, Version=1.0.0.0, Culture=neutral, PublicKeyToken=bad199fe84eb3df4, processorArchitecture=MSIL">
|
||||
<SpecificVersion>False</SpecificVersion>
|
||||
</Reference>
|
||||
<Reference Include="Sharp3D.Math, Version=1.1.3.0, Culture=neutral, PublicKeyToken=529e2e82fcc0ba71">
|
||||
<SpecificVersion>False</SpecificVersion>
|
||||
<HintPath>Lib\Sharp3D.Math.dll</HintPath>
|
||||
</Reference>
|
||||
<Reference Include="SharpKml, Version=1.1.0.0, Culture=neutral, PublicKeyToken=e608cd7d975805ad, processorArchitecture=MSIL">
|
||||
<SpecificVersion>False</SpecificVersion>
|
||||
</Reference>
|
||||
@ -290,7 +286,6 @@
|
||||
<Compile Include="GCSViews\ConfigurationView\ConfigMount.designer.cs">
|
||||
<DependentUpon>ConfigMount.cs</DependentUpon>
|
||||
</Compile>
|
||||
<Compile Include="HIL\FlashQuad.cs" />
|
||||
<Compile Include="HIL\Matrix3.cs" />
|
||||
<Compile Include="HIL\Vector3.cs" />
|
||||
<Compile Include="Presenter\ConfigCameraStabPresenter.cs" />
|
||||
|
@ -377,7 +377,7 @@ namespace ArdupilotMega
|
||||
if (DateTime.Now.Second != lastwindcalc.Second)
|
||||
{
|
||||
lastwindcalc = DateTime.Now;
|
||||
dowindcalc();
|
||||
// dowindcalc();
|
||||
}
|
||||
|
||||
if (mavinterface.packets[MAVLink.MAVLINK_MSG_ID_STATUSTEXT] != null) // status text
|
||||
@ -446,6 +446,17 @@ namespace ArdupilotMega
|
||||
//MAVLink.packets[MAVLink.MAVLINK_MSG_ID_HWSTATUS] = null;
|
||||
}
|
||||
|
||||
bytearray = mavinterface.packets[ArdupilotMega.MAVLink.MAVLINK_MSG_ID_WIND];
|
||||
if (bytearray != null)
|
||||
{
|
||||
var wind = bytearray.ByteArrayToStructure<MAVLink.mavlink_wind_t>(6);
|
||||
|
||||
wind_dir = wind.direction;
|
||||
wind_vel = wind.speed;
|
||||
|
||||
//MAVLink.packets[ArdupilotMega.MAVLink.MAVLINK_MSG_ID_SYS_STATUS] = null;
|
||||
}
|
||||
|
||||
#if MAVLINK10
|
||||
|
||||
|
||||
@ -951,6 +962,8 @@ namespace ArdupilotMega
|
||||
|
||||
alt = vfr.alt; // this might include baro
|
||||
|
||||
//Console.WriteLine(alt);
|
||||
|
||||
//climbrate = vfr.climb;
|
||||
|
||||
if ((DateTime.Now - lastalt).TotalSeconds >= 0.2 && oldalt != alt)
|
||||
|
@ -365,7 +365,7 @@ namespace ArdupilotMega.GCSViews.ConfigurationView
|
||||
for (int i = 0; i < descriptionParts.Length; i++)
|
||||
{
|
||||
returnDescription.Append(String.Format("{0} ", descriptionParts[i]));
|
||||
if (i != 0 && i % 10 == 0) returnDescription.Append(Environment.NewLine);
|
||||
if (i != 0 && i % 12 == 0) returnDescription.Append(Environment.NewLine);
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -591,6 +591,7 @@
|
||||
this.comboBoxMapType.FormattingEnabled = true;
|
||||
this.comboBoxMapType.Name = "comboBoxMapType";
|
||||
this.toolTip1.SetToolTip(this.comboBoxMapType, resources.GetString("comboBoxMapType.ToolTip"));
|
||||
this.comboBoxMapType.SelectedIndexChanged += new System.EventHandler(this.comboBoxMapType_SelectedValueChanged);
|
||||
//
|
||||
// panelMap
|
||||
//
|
||||
|
@ -3221,8 +3221,8 @@ namespace ArdupilotMega.GCSViews
|
||||
string distance = (50 * MainV2.cs.multiplierdist).ToString("0");
|
||||
Common.InputBox("Distance", "Distance between lines", ref distance);
|
||||
|
||||
//string overshoot = (30 * MainV2.cs.multiplierdist).ToString("0");
|
||||
//Common.InputBox("Overshoot", "Enter of line overshoot amount", ref overshoot);
|
||||
string wpevery = (40 * MainV2.cs.multiplierdist).ToString("0");
|
||||
Common.InputBox("Every", "Put a WP every x distance (-1 for none)", ref wpevery);
|
||||
|
||||
string angle = (90).ToString("0");
|
||||
Common.InputBox("Angle", "Enter the line direction (0-180)", ref angle);
|
||||
@ -3244,6 +3244,11 @@ namespace ArdupilotMega.GCSViews
|
||||
CustomMessageBox.Show("Invalid Distance");
|
||||
return;
|
||||
}
|
||||
if (!double.TryParse(wpevery, out tryme))
|
||||
{
|
||||
CustomMessageBox.Show("Invalid Waypoint spacing");
|
||||
return;
|
||||
}
|
||||
|
||||
#if DEBUG
|
||||
//Commands.Rows.Clear();
|
||||
@ -3274,12 +3279,18 @@ namespace ArdupilotMega.GCSViews
|
||||
|
||||
int count = 0;
|
||||
|
||||
double x = bottomleft.Lat - Math.Abs(fulllatdiff);
|
||||
double y = bottomleft.Lng - Math.Abs(fulllngdiff);
|
||||
double x = bottomleft.Lat - Math.Abs(fulllatdiff) - latlngdiff * 0.5;
|
||||
double y = bottomleft.Lng - Math.Abs(fulllngdiff) - latlngdiff * 0.5;
|
||||
|
||||
//callMe(x, y, 0);
|
||||
|
||||
//callMe(topright.Lat + Math.Abs(latlngdiff),topright.Lng + Math.Abs(latlngdiff), 0);
|
||||
|
||||
//return;
|
||||
|
||||
log.InfoFormat("{0} < {1} {2} < {3}", x, (topright.Lat), y, (topright.Lng));
|
||||
|
||||
while (x < (topright.Lat + Math.Abs(fulllatdiff)) && y < (topright.Lng + Math.Abs(fulllngdiff)))
|
||||
while (x < (topright.Lat + Math.Abs(latlngdiff)) && y < (topright.Lng + Math.Abs(latlngdiff)))
|
||||
{
|
||||
if (double.Parse(angle) < 45)
|
||||
{
|
||||
@ -3348,9 +3359,24 @@ namespace ArdupilotMega.GCSViews
|
||||
}
|
||||
|
||||
if (!farestlatlong.IsZero)
|
||||
{
|
||||
callMe(farestlatlong.Lat, farestlatlong.Lng, altitude);
|
||||
}
|
||||
if (!closestlatlong.IsZero && !farestlatlong.IsZero && double.Parse(wpevery) > 0)
|
||||
{
|
||||
for (int d = (int)double.Parse(wpevery); d < (MainMap.Manager.GetDistance(farestlatlong, closestlatlong) * 1000); d += (int)double.Parse(wpevery))
|
||||
{
|
||||
ax = farestlatlong.Lat;
|
||||
ay = farestlatlong.Lng;
|
||||
|
||||
newpos(ref ax, ref ay, double.Parse(angle), -d);
|
||||
callMe(ax, ay, altitude);
|
||||
}
|
||||
}
|
||||
if (!closestlatlong.IsZero)
|
||||
{
|
||||
callMe(closestlatlong.Lat, closestlatlong.Lng - overshootdistlng, altitude);
|
||||
}
|
||||
|
||||
//callMe(x, topright.Lng, altitude);
|
||||
//callMe(x, bottomleft.Lng - overshootdistlng, altitude);
|
||||
@ -3389,9 +3415,24 @@ namespace ArdupilotMega.GCSViews
|
||||
}
|
||||
}
|
||||
if (!closestlatlong.IsZero)
|
||||
{
|
||||
callMe(closestlatlong.Lat, closestlatlong.Lng, altitude);
|
||||
}
|
||||
if (!closestlatlong.IsZero && !farestlatlong.IsZero && double.Parse(wpevery) > 0)
|
||||
{
|
||||
for (int d = (int)double.Parse(wpevery); d < (MainMap.Manager.GetDistance(farestlatlong, closestlatlong) * 1000); d += (int)double.Parse(wpevery))
|
||||
{
|
||||
ax = closestlatlong.Lat;
|
||||
ay = closestlatlong.Lng;
|
||||
|
||||
newpos(ref ax, ref ay, double.Parse(angle), d);
|
||||
callMe(ax, ay, altitude);
|
||||
}
|
||||
}
|
||||
if (!farestlatlong.IsZero)
|
||||
{
|
||||
callMe(farestlatlong.Lat, farestlatlong.Lng + overshootdistlng, altitude);
|
||||
}
|
||||
//callMe(x, bottomleft.Lng, altitude);
|
||||
//callMe(x, topright.Lng + overshootdistlng, altitude);
|
||||
}
|
||||
@ -3414,6 +3455,38 @@ namespace ArdupilotMega.GCSViews
|
||||
}
|
||||
}
|
||||
|
||||
void newpos(ref double lat, ref double lon, double bearing, double distance)
|
||||
{
|
||||
// '''extrapolate latitude/longitude given a heading and distance
|
||||
// thanks to http://www.movable-type.co.uk/scripts/latlong.html
|
||||
// '''
|
||||
// from math import sin, asin, cos, atan2, radians, degrees
|
||||
double radius_of_earth = 6378100.0;//# in meters
|
||||
|
||||
double lat1 = radians(lat);
|
||||
double lon1 = radians(lon);
|
||||
double brng = radians(bearing);
|
||||
double dr = distance / radius_of_earth;
|
||||
|
||||
double lat2 = Math.Asin(Math.Sin(lat1) * Math.Cos(dr) +
|
||||
Math.Cos(lat1) * Math.Sin(dr) * Math.Cos(brng));
|
||||
double lon2 = lon1 + Math.Atan2(Math.Sin(brng) * Math.Sin(dr) * Math.Cos(lat1),
|
||||
Math.Cos(dr) - Math.Sin(lat1) * Math.Sin(lat2));
|
||||
|
||||
lat = degrees(lat2);
|
||||
lon = degrees(lon2);
|
||||
//return (degrees(lat2), degrees(lon2));
|
||||
}
|
||||
|
||||
public static double radians(double val)
|
||||
{
|
||||
return val * deg2rad;
|
||||
}
|
||||
public static double degrees(double val)
|
||||
{
|
||||
return val * rad2deg;
|
||||
}
|
||||
|
||||
private void zoomToToolStripMenuItem_Click(object sender, EventArgs e)
|
||||
{
|
||||
string place = "Perth Airport, Australia";
|
||||
|
@ -322,7 +322,7 @@
|
||||
<value>3, 55</value>
|
||||
</data>
|
||||
<data name="Commands.RowHeadersWidth" type="System.Int32, mscorlib">
|
||||
<value>35</value>
|
||||
<value>45</value>
|
||||
</data>
|
||||
<data name="Commands.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>610, 79</value>
|
||||
@ -556,7 +556,7 @@
|
||||
<value>BUT_write</value>
|
||||
</data>
|
||||
<data name=">>BUT_write.Type" xml:space="preserve">
|
||||
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4611.35137, Culture=neutral, PublicKeyToken=null</value>
|
||||
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4613.14163, Culture=neutral, PublicKeyToken=null</value>
|
||||
</data>
|
||||
<data name=">>BUT_write.Parent" xml:space="preserve">
|
||||
<value>panel5</value>
|
||||
@ -583,7 +583,7 @@
|
||||
<value>BUT_read</value>
|
||||
</data>
|
||||
<data name=">>BUT_read.Type" xml:space="preserve">
|
||||
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4611.35137, Culture=neutral, PublicKeyToken=null</value>
|
||||
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4613.14163, Culture=neutral, PublicKeyToken=null</value>
|
||||
</data>
|
||||
<data name=">>BUT_read.Parent" xml:space="preserve">
|
||||
<value>panel5</value>
|
||||
@ -1147,7 +1147,7 @@
|
||||
<value>BUT_Add</value>
|
||||
</data>
|
||||
<data name=">>BUT_Add.Type" xml:space="preserve">
|
||||
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4611.35137, Culture=neutral, PublicKeyToken=null</value>
|
||||
<value>ArdupilotMega.Controls.MyButton, ArdupilotMegaPlanner10, Version=1.1.4613.14163, Culture=neutral, PublicKeyToken=null</value>
|
||||
</data>
|
||||
<data name=">>BUT_Add.Parent" xml:space="preserve">
|
||||
<value>panelWaypoints</value>
|
||||
@ -1742,7 +1742,7 @@
|
||||
<value>MainMap</value>
|
||||
</data>
|
||||
<data name=">>MainMap.Type" xml:space="preserve">
|
||||
<value>ArdupilotMega.Controls.myGMAP, ArdupilotMegaPlanner10, Version=1.1.4611.35137, Culture=neutral, PublicKeyToken=null</value>
|
||||
<value>ArdupilotMega.Controls.myGMAP, ArdupilotMegaPlanner10, Version=1.1.4613.14163, Culture=neutral, PublicKeyToken=null</value>
|
||||
</data>
|
||||
<data name=">>MainMap.Parent" xml:space="preserve">
|
||||
<value>panelMap</value>
|
||||
@ -1772,7 +1772,7 @@
|
||||
<value>trackBar1</value>
|
||||
</data>
|
||||
<data name=">>trackBar1.Type" xml:space="preserve">
|
||||
<value>ArdupilotMega.Controls.MyTrackBar, ArdupilotMegaPlanner10, Version=1.1.4611.35137, Culture=neutral, PublicKeyToken=null</value>
|
||||
<value>ArdupilotMega.Controls.MyTrackBar, ArdupilotMegaPlanner10, Version=1.1.4613.14163, Culture=neutral, PublicKeyToken=null</value>
|
||||
</data>
|
||||
<data name=">>trackBar1.Parent" xml:space="preserve">
|
||||
<value>panelMap</value>
|
||||
@ -2219,6 +2219,6 @@
|
||||
<value>FlightPlanner</value>
|
||||
</data>
|
||||
<data name=">>$this.Type" xml:space="preserve">
|
||||
<value>System.Windows.Forms.MyUserControl, ArdupilotMegaPlanner10, Version=1.1.4611.35137, Culture=neutral, PublicKeyToken=null</value>
|
||||
<value>System.Windows.Forms.MyUserControl, ArdupilotMegaPlanner10, Version=1.1.4613.14163, Culture=neutral, PublicKeyToken=null</value>
|
||||
</data>
|
||||
</root>
|
@ -1022,7 +1022,7 @@ namespace ArdupilotMega.GCSViews
|
||||
// Console.WriteLine(hilstate.alt);
|
||||
|
||||
hilstate.pitch = (float)sitldata.pitchDeg * deg2rad; // (rad)
|
||||
hilstate.pitchspeed = (float)sitldata.pitchRate * rad2deg; // (rad/s)
|
||||
hilstate.pitchspeed = (float)sitldata.pitchRate * deg2rad; // (rad/s)
|
||||
hilstate.roll = (float)sitldata.rollDeg * deg2rad; // (rad)
|
||||
hilstate.rollspeed = (float)sitldata.rollRate * deg2rad; // (rad/s)
|
||||
hilstate.yaw = (float)sitldata.yawDeg * deg2rad; // (rad)
|
||||
@ -1266,7 +1266,10 @@ namespace ArdupilotMega.GCSViews
|
||||
|
||||
if (RAD_aerosimrc.Checked)
|
||||
{
|
||||
updateScreenDisplay(aeroin.Model_fLatitude * deg2rad, aeroin.Model_fLongitude * deg2rad, aeroin.Model_fPosZ, aeroin.Model_fRoll, aeroin.Model_fPitch, aeroin.Model_fHeading, aeroin.Model_fHeading, roll_out, pitch_out, rudder_out, throttle_out);
|
||||
if (heli)
|
||||
updateScreenDisplay(aeroin.Model_fLatitude * deg2rad, aeroin.Model_fLongitude * deg2rad, aeroin.Model_fPosZ, aeroin.Model_fRoll, aeroin.Model_fPitch, aeroin.Model_fHeading, aeroin.Model_fHeading, roll_out, pitch_out, rudder_out, collective_out);
|
||||
else
|
||||
updateScreenDisplay(aeroin.Model_fLatitude * deg2rad, aeroin.Model_fLongitude * deg2rad, aeroin.Model_fPosZ, aeroin.Model_fRoll, aeroin.Model_fPitch, aeroin.Model_fHeading, aeroin.Model_fHeading, roll_out, pitch_out, rudder_out, throttle_out);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -2071,11 +2071,11 @@ namespace ArdupilotMega
|
||||
frm.Show();
|
||||
return true;
|
||||
}
|
||||
if (keyData == (Keys.Control | Keys.S)) // screenshot
|
||||
/*if (keyData == (Keys.Control | Keys.S)) // screenshot
|
||||
{
|
||||
ScreenShot();
|
||||
return true;
|
||||
}
|
||||
}*/
|
||||
if (keyData == (Keys.Control | Keys.G)) // nmea out
|
||||
{
|
||||
Form frm = new SerialOutput();
|
||||
|
@ -8,9 +8,9 @@ namespace ArdupilotMega
|
||||
#if MAVLINK10
|
||||
partial class MAVLink
|
||||
{
|
||||
public const string MAVLINK_BUILD_DATE = "Thu Jul 26 18:28:25 2012";
|
||||
public const string MAVLINK_BUILD_DATE = "Sat Aug 18 07:50:27 2012";
|
||||
public const string MAVLINK_WIRE_PROTOCOL_VERSION = "1.0";
|
||||
public const int MAVLINK_MAX_DIALECT_PAYLOAD_SIZE = 42;
|
||||
public const int MAVLINK_MAX_DIALECT_PAYLOAD_SIZE = 101;
|
||||
|
||||
public const int MAVLINK_LITTLE_ENDIAN = 1;
|
||||
public const int MAVLINK_BIG_ENDIAN = 0;
|
||||
@ -25,11 +25,11 @@ namespace ArdupilotMega
|
||||
|
||||
public const bool MAVLINK_NEED_BYTE_SWAP = (MAVLINK_ENDIAN == MAVLINK_LITTLE_ENDIAN);
|
||||
|
||||
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, 9, 34, 26, 46, 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, 28, 56, 42, 33, 0, 0, 0, 0, 0, 0, 0, 26, 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, 44, 3, 9, 22, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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, 0};
|
||||
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, 9, 34, 26, 46, 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, 28, 56, 42, 33, 0, 0, 0, 0, 0, 0, 0, 26, 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, 44, 3, 9, 22, 12, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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, 0};
|
||||
|
||||
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, 30, 240, 183, 130, 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, 231, 183, 63, 54, 0, 0, 0, 0, 0, 0, 0, 175, 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, 111, 21, 21, 144, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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, 0};
|
||||
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, 30, 240, 183, 130, 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, 231, 183, 63, 54, 0, 0, 0, 0, 0, 0, 0, 175, 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, 111, 21, 21, 144, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 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, 0};
|
||||
|
||||
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 ), typeof( mavlink_set_quad_motors_setpoint_t ), typeof( mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t ), typeof( mavlink_nav_controller_output_t ), typeof( mavlink_set_quad_swarm_led_roll_pitch_yaw_thrust_t ), 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, typeof( mavlink_local_position_ned_system_global_offset_t ), 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 ), typeof( mavlink_limits_status_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, 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 ), null};
|
||||
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 ), typeof( mavlink_set_quad_motors_setpoint_t ), typeof( mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t ), typeof( mavlink_nav_controller_output_t ), typeof( mavlink_set_quad_swarm_led_roll_pitch_yaw_thrust_t ), 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, typeof( mavlink_local_position_ned_system_global_offset_t ), 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 ), typeof( mavlink_limits_status_t ), typeof( mavlink_wind_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, 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 ), null};
|
||||
|
||||
public const byte MAVLINK_VERSION = 2;
|
||||
|
||||
@ -141,8 +141,10 @@ namespace ArdupilotMega
|
||||
NONE=0,
|
||||
///<summary> Switched to guided mode to return point (fence point 0) | </summary>
|
||||
GUIDED=1,
|
||||
///<summary> Report fence breach, but don't take action | </summary>
|
||||
REPORT=2,
|
||||
///<summary> | </summary>
|
||||
ENUM_END=2,
|
||||
ENUM_END=3,
|
||||
|
||||
};
|
||||
|
||||
@ -490,7 +492,7 @@ namespace ArdupilotMega
|
||||
|
||||
};
|
||||
|
||||
/** @brief Data stream IDs. A data stream is not a fixed set of messages, but rather a recommendation to the autopilot software. Individual autopilots may or may not obey the recommended messages. */
|
||||
/** @brief Data stream IDs. A data stream is not a fixed set of messages, but rather a recommendation to the autopilot software. Individual autopilots may or may not obey the recommended messages. */
|
||||
public enum MAV_DATA_STREAM
|
||||
{
|
||||
///<summary> Enable all data streams | </summary>
|
||||
@ -516,7 +518,7 @@ namespace ArdupilotMega
|
||||
|
||||
};
|
||||
|
||||
/** @brief The ROI (region of interest) for the vehicle. This can be be used by the vehicle for camera/vehicle attitude alignment (see MAV_CMD_NAV_ROI). */
|
||||
/** @brief The ROI (region of interest) for the vehicle. This can be be used by the vehicle for camera/vehicle attitude alignment (see MAV_CMD_NAV_ROI). */
|
||||
public enum MAV_ROI
|
||||
{
|
||||
///<summary> No region of interest. | </summary>
|
||||
@ -912,7 +914,7 @@ namespace ArdupilotMega
|
||||
|
||||
|
||||
public const byte MAVLINK_MSG_ID_SIMSTATE = 164;
|
||||
[StructLayout(LayoutKind.Sequential,Pack=1,Size=36)]
|
||||
[StructLayout(LayoutKind.Sequential,Pack=1,Size=44)]
|
||||
public struct mavlink_simstate_t
|
||||
{
|
||||
/// <summary> Roll angle (rad) </summary>
|
||||
@ -933,8 +935,11 @@ namespace ArdupilotMega
|
||||
public Single ygyro;
|
||||
/// <summary> Angular speed around Z axis rad/s </summary>
|
||||
public Single zgyro;
|
||||
public Single lat;
|
||||
public Single lng;
|
||||
/// <summary> Latitude in degrees </summary>
|
||||
public Single lat;
|
||||
/// <summary> Longitude in degrees </summary>
|
||||
public Single lng;
|
||||
|
||||
};
|
||||
|
||||
|
||||
@ -998,21 +1003,35 @@ namespace ArdupilotMega
|
||||
};
|
||||
|
||||
|
||||
public const byte MAVLINK_MSG_ID_WIND = 168;
|
||||
[StructLayout(LayoutKind.Sequential,Pack=1,Size=12)]
|
||||
public struct mavlink_wind_t
|
||||
{
|
||||
/// <summary> wind direction (degrees) </summary>
|
||||
public Single direction;
|
||||
/// <summary> wind speed in ground plane (m/s) </summary>
|
||||
public Single speed;
|
||||
/// <summary> vertical wind speed (m/s) </summary>
|
||||
public Single speed_z;
|
||||
|
||||
};
|
||||
|
||||
|
||||
public const byte MAVLINK_MSG_ID_HEARTBEAT = 0;
|
||||
[StructLayout(LayoutKind.Sequential,Pack=1,Size=9)]
|
||||
public struct mavlink_heartbeat_t
|
||||
{
|
||||
/// <summary> Navigation mode bitfield, see MAV_AUTOPILOT_CUSTOM_MODE ENUM for some examples. This field is autopilot-specific. </summary>
|
||||
/// <summary> A bitfield for use for autopilot-specific flags. </summary>
|
||||
public UInt32 custom_mode;
|
||||
/// <summary> Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) </summary>
|
||||
public byte type;
|
||||
/// <summary> Autopilot type / class. defined in MAV_CLASS ENUM </summary>
|
||||
/// <summary> Autopilot type / class. defined in MAV_AUTOPILOT ENUM </summary>
|
||||
public byte autopilot;
|
||||
/// <summary> System mode bitfield, see MAV_MODE_FLAGS ENUM in mavlink/include/mavlink_types.h </summary>
|
||||
public byte base_mode;
|
||||
/// <summary> System status flag, see MAV_STATUS ENUM </summary>
|
||||
/// <summary> System status flag, see MAV_STATE ENUM </summary>
|
||||
public byte system_status;
|
||||
/// <summary> MAVLink version </summary>
|
||||
/// <summary> MAVLink version, not writable by user, gets added by protocol because of magic data type: uint8_t_mavlink_version </summary>
|
||||
public byte mavlink_version;
|
||||
|
||||
};
|
||||
@ -1092,7 +1111,7 @@ namespace ArdupilotMega
|
||||
public byte version;
|
||||
/// <summary> Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-" </summary>
|
||||
[MarshalAs(UnmanagedType.ByValArray,SizeConst=25)]
|
||||
public string passkey;
|
||||
public byte[] passkey;
|
||||
|
||||
};
|
||||
|
||||
@ -1117,7 +1136,7 @@ namespace ArdupilotMega
|
||||
{
|
||||
/// <summary> key </summary>
|
||||
[MarshalAs(UnmanagedType.ByValArray,SizeConst=32)]
|
||||
public string key;
|
||||
public byte[] key;
|
||||
|
||||
};
|
||||
|
||||
@ -1140,15 +1159,15 @@ namespace ArdupilotMega
|
||||
[StructLayout(LayoutKind.Sequential,Pack=1,Size=20)]
|
||||
public struct mavlink_param_request_read_t
|
||||
{
|
||||
/// <summary> Parameter index. Send -1 to use the param ID field as identifier </summary>
|
||||
/// <summary> Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored) </summary>
|
||||
public Int16 param_index;
|
||||
/// <summary> System ID </summary>
|
||||
public byte target_system;
|
||||
/// <summary> Component ID </summary>
|
||||
public byte target_component;
|
||||
/// <summary> Onboard parameter id </summary>
|
||||
/// <summary> Onboard parameter id, terminated by NUL if the length is less than 16 human-readable chars and WITHOUT null termination (NUL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string </summary>
|
||||
[MarshalAs(UnmanagedType.ByValArray,SizeConst=16)]
|
||||
public string param_id;
|
||||
public byte[] param_id;
|
||||
|
||||
};
|
||||
|
||||
@ -1175,10 +1194,10 @@ namespace ArdupilotMega
|
||||
public UInt16 param_count;
|
||||
/// <summary> Index of this onboard parameter </summary>
|
||||
public UInt16 param_index;
|
||||
/// <summary> Onboard parameter id </summary>
|
||||
/// <summary> Onboard parameter id, terminated by NUL if the length is less than 16 human-readable chars and WITHOUT null termination (NUL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string </summary>
|
||||
[MarshalAs(UnmanagedType.ByValArray,SizeConst=16)]
|
||||
public byte[] param_id;
|
||||
/// <summary> Onboard parameter type: see MAV_VAR enum </summary>
|
||||
/// <summary> Onboard parameter type: see MAVLINK_TYPE enum in mavlink/mavlink_types.h </summary>
|
||||
public byte param_type;
|
||||
|
||||
};
|
||||
@ -1194,10 +1213,10 @@ namespace ArdupilotMega
|
||||
public byte target_system;
|
||||
/// <summary> Component ID </summary>
|
||||
public byte target_component;
|
||||
/// <summary> Onboard parameter id </summary>
|
||||
/// <summary> Onboard parameter id, terminated by NUL if the length is less than 16 human-readable chars and WITHOUT null termination (NUL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string </summary>
|
||||
[MarshalAs(UnmanagedType.ByValArray,SizeConst=16)]
|
||||
public byte[] param_id;
|
||||
/// <summary> Onboard parameter type: see MAV_VAR enum </summary>
|
||||
public byte[] param_id;
|
||||
/// <summary> Onboard parameter type: see MAVLINK_TYPE enum in mavlink/mavlink_types.h </summary>
|
||||
public byte param_type;
|
||||
|
||||
};
|
||||
@ -1334,7 +1353,7 @@ namespace ArdupilotMega
|
||||
[StructLayout(LayoutKind.Sequential,Pack=1,Size=14)]
|
||||
public struct mavlink_scaled_pressure_t
|
||||
{
|
||||
/// <summary> Timestamp (microseconds since UNIX epoch or microseconds since system boot) </summary>
|
||||
/// <summary> Timestamp (milliseconds since system boot) </summary>
|
||||
public UInt32 time_boot_ms;
|
||||
/// <summary> Absolute pressure (hectopascal) </summary>
|
||||
public Single press_abs;
|
||||
@ -1504,7 +1523,7 @@ namespace ArdupilotMega
|
||||
[StructLayout(LayoutKind.Sequential,Pack=1,Size=21)]
|
||||
public struct mavlink_servo_output_raw_t
|
||||
{
|
||||
/// <summary> Timestamp (since UNIX epoch or microseconds since system boot) </summary>
|
||||
/// <summary> Timestamp (microseconds since system boot) </summary>
|
||||
public UInt32 time_usec;
|
||||
/// <summary> Servo output 1 value, in microseconds </summary>
|
||||
public UInt16 servo1_raw;
|
||||
@ -1950,16 +1969,16 @@ namespace ArdupilotMega
|
||||
{
|
||||
/// <summary> Desired roll angle in radians +-PI (+-32767) </summary>
|
||||
[MarshalAs(UnmanagedType.ByValArray,SizeConst=4)]
|
||||
public Int16[] roll;
|
||||
public Int16[] roll;
|
||||
/// <summary> Desired pitch angle in radians +-PI (+-32767) </summary>
|
||||
[MarshalAs(UnmanagedType.ByValArray,SizeConst=4)]
|
||||
public Int16[] pitch;
|
||||
public Int16[] pitch;
|
||||
/// <summary> Desired yaw angle in radians, scaled to int16 +-PI (+-32767) </summary>
|
||||
[MarshalAs(UnmanagedType.ByValArray,SizeConst=4)]
|
||||
public Int16[] yaw;
|
||||
public Int16[] yaw;
|
||||
/// <summary> Collective thrust, scaled to uint16 (0..65535) </summary>
|
||||
[MarshalAs(UnmanagedType.ByValArray,SizeConst=4)]
|
||||
public UInt16[] thrust;
|
||||
public UInt16[] thrust;
|
||||
/// <summary> ID of the quadrotor group (0 - 255, up to 256 groups supported) </summary>
|
||||
public byte group;
|
||||
/// <summary> ID of the flight mode (0 - 255, up to 256 modes supported) </summary>
|
||||
@ -1998,16 +2017,16 @@ namespace ArdupilotMega
|
||||
{
|
||||
/// <summary> Desired roll angle in radians +-PI (+-32767) </summary>
|
||||
[MarshalAs(UnmanagedType.ByValArray,SizeConst=4)]
|
||||
public Int16[] roll;
|
||||
public Int16[] roll;
|
||||
/// <summary> Desired pitch angle in radians +-PI (+-32767) </summary>
|
||||
[MarshalAs(UnmanagedType.ByValArray,SizeConst=4)]
|
||||
public Int16[] pitch;
|
||||
public Int16[] pitch;
|
||||
/// <summary> Desired yaw angle in radians, scaled to int16 +-PI (+-32767) </summary>
|
||||
[MarshalAs(UnmanagedType.ByValArray,SizeConst=4)]
|
||||
public Int16[] yaw;
|
||||
public Int16[] yaw;
|
||||
/// <summary> Collective thrust, scaled to uint16 (0..65535) </summary>
|
||||
[MarshalAs(UnmanagedType.ByValArray,SizeConst=4)]
|
||||
public UInt16[] thrust;
|
||||
public UInt16[] thrust;
|
||||
/// <summary> ID of the quadrotor group (0 - 255, up to 256 groups supported) </summary>
|
||||
public byte group;
|
||||
/// <summary> ID of the flight mode (0 - 255, up to 256 modes supported) </summary>
|
||||
@ -2464,7 +2483,7 @@ namespace ArdupilotMega
|
||||
public Single z;
|
||||
/// <summary> Name </summary>
|
||||
[MarshalAs(UnmanagedType.ByValArray,SizeConst=10)]
|
||||
public string name;
|
||||
public byte[] name;
|
||||
|
||||
};
|
||||
|
||||
@ -2479,7 +2498,7 @@ namespace ArdupilotMega
|
||||
public Single value;
|
||||
/// <summary> Name of the debug variable </summary>
|
||||
[MarshalAs(UnmanagedType.ByValArray,SizeConst=10)]
|
||||
public string name;
|
||||
public byte[] name;
|
||||
|
||||
};
|
||||
|
||||
@ -2494,7 +2513,7 @@ namespace ArdupilotMega
|
||||
public Int32 value;
|
||||
/// <summary> Name of the debug variable </summary>
|
||||
[MarshalAs(UnmanagedType.ByValArray,SizeConst=10)]
|
||||
public string name;
|
||||
public byte[] name;
|
||||
|
||||
};
|
||||
|
||||
@ -2503,11 +2522,11 @@ namespace ArdupilotMega
|
||||
[StructLayout(LayoutKind.Sequential,Pack=1,Size=51)]
|
||||
public struct mavlink_statustext_t
|
||||
{
|
||||
/// <summary> Severity of status, 0 = info message, 255 = critical fault </summary>
|
||||
/// <summary> Severity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY. </summary>
|
||||
public byte severity;
|
||||
/// <summary> Status text message, without null termination character </summary>
|
||||
[MarshalAs(UnmanagedType.ByValArray,SizeConst=50)]
|
||||
public string text;
|
||||
public byte[] text;
|
||||
|
||||
};
|
||||
|
||||
|
@ -2,14 +2,14 @@
|
||||
<Wix xmlns="http://schemas.microsoft.com/wix/2006/wi" xmlns:netfx="http://schemas.microsoft.com/wix/NetFxExtension" xmlns:difx="http://schemas.microsoft.com/wix/DifxAppExtension">
|
||||
|
||||
|
||||
<Product Id="*" Name="APM Planner" Language="1033" Version="1.2.5" Manufacturer="Michael Oborne" UpgradeCode="{625389D7-EB3C-4d77-A5F6-A285CF99437D}">
|
||||
<Product Id="*" Name="APM Planner" Language="1033" Version="1.2.6" Manufacturer="Michael Oborne" UpgradeCode="{625389D7-EB3C-4d77-A5F6-A285CF99437D}">
|
||||
|
||||
<Package Description="APM Planner Installer" Comments="Apm Planner Installer" Manufacturer="Michael Oborne" InstallerVersion="200" Compressed="yes" />
|
||||
|
||||
|
||||
<Upgrade Id="{625389D7-EB3C-4d77-A5F6-A285CF99437D}">
|
||||
<UpgradeVersion OnlyDetect="yes" Minimum="1.2.5" Property="NEWERVERSIONDETECTED" IncludeMinimum="no" />
|
||||
<UpgradeVersion OnlyDetect="no" Maximum="1.2.5" Property="OLDERVERSIONBEINGUPGRADED" IncludeMaximum="no" />
|
||||
<UpgradeVersion OnlyDetect="yes" Minimum="1.2.6" Property="NEWERVERSIONDETECTED" IncludeMinimum="no" />
|
||||
<UpgradeVersion OnlyDetect="no" Maximum="1.2.6" Property="OLDERVERSIONBEINGUPGRADED" IncludeMaximum="no" />
|
||||
</Upgrade>
|
||||
|
||||
<InstallExecuteSequence>
|
||||
@ -31,7 +31,7 @@
|
||||
<Permission User="Everyone" GenericAll="yes" />
|
||||
</CreateFolder>
|
||||
</Component>
|
||||
<Component Id="_comp1" Guid="a550f246-9f75-42dd-a880-de05e84d6da3">
|
||||
<Component Id="_comp1" Guid="2682a639-9b2c-49ae-8fc0-97a69b4f2bd2">
|
||||
<File Id="_2" Source="..\bin\release\.gdbinit" />
|
||||
<File Id="_3" Source="..\bin\release\.gitignore" />
|
||||
<File Id="_4" Source="..\bin\release\aerosim3.91.txt" />
|
||||
@ -113,11 +113,11 @@
|
||||
<File Id="_80" Source="..\bin\release\ZedGraph.dll" />
|
||||
</Component>
|
||||
<Directory Id="aircraft80" Name="aircraft">
|
||||
<Component Id="_comp81" Guid="28568d43-5eff-49bc-a09b-ba54d3116185">
|
||||
<Component Id="_comp81" Guid="937e663c-1477-41c3-8db9-28421c35edf8">
|
||||
<File Id="_82" Source="..\bin\release\aircraft\placeholder.txt" />
|
||||
</Component>
|
||||
<Directory Id="arducopter82" Name="arducopter">
|
||||
<Component Id="_comp83" Guid="2e144ab3-cce2-4fcc-84cc-e4b8850173a8">
|
||||
<Component Id="_comp83" Guid="79e4b778-df2d-4b85-9b30-330377b54e81">
|
||||
<File Id="_84" Source="..\bin\release\aircraft\arducopter\arducopter-set.xml" />
|
||||
<File Id="_85" Source="..\bin\release\aircraft\arducopter\arducopter.jpg" />
|
||||
<File Id="_86" Source="..\bin\release\aircraft\arducopter\arducopter.xml" />
|
||||
@ -128,20 +128,20 @@
|
||||
<File Id="_91" Source="..\bin\release\aircraft\arducopter\README" />
|
||||
</Component>
|
||||
<Directory Id="data91" Name="data">
|
||||
<Component Id="_comp92" Guid="29b7d782-4939-4a7b-b740-8bb062f30324">
|
||||
<Component Id="_comp92" Guid="44cf39a9-71df-492f-9b83-c2c2076f79bc">
|
||||
<File Id="_93" Source="..\bin\release\aircraft\arducopter\data\arducopter_half_step.txt" />
|
||||
<File Id="_94" Source="..\bin\release\aircraft\arducopter\data\arducopter_step.txt" />
|
||||
<File Id="_95" Source="..\bin\release\aircraft\arducopter\data\rw_generic_pylon.ac" />
|
||||
</Component>
|
||||
</Directory>
|
||||
<Directory Id="Engines95" Name="Engines">
|
||||
<Component Id="_comp96" Guid="69e8b8da-34f9-41b2-9325-caff303d919c">
|
||||
<Component Id="_comp96" Guid="354ecdad-7339-4361-b0fc-e1c264c4b9c5">
|
||||
<File Id="_97" Source="..\bin\release\aircraft\arducopter\Engines\a2830-12.xml" />
|
||||
<File Id="_98" Source="..\bin\release\aircraft\arducopter\Engines\prop10x4.5.xml" />
|
||||
</Component>
|
||||
</Directory>
|
||||
<Directory Id="Models98" Name="Models">
|
||||
<Component Id="_comp99" Guid="70b6839a-af81-4e6c-bbd2-974ffda97f29">
|
||||
<Component Id="_comp99" Guid="fedc8251-7e93-42fe-bf2c-1ca4a9a45a54">
|
||||
<File Id="_100" Source="..\bin\release\aircraft\arducopter\Models\arducopter.ac" />
|
||||
<File Id="_101" Source="..\bin\release\aircraft\arducopter\Models\arducopter.xml" />
|
||||
<File Id="_102" Source="..\bin\release\aircraft\arducopter\Models\plus_quad.ac" />
|
||||
@ -155,7 +155,7 @@
|
||||
</Directory>
|
||||
</Directory>
|
||||
<Directory Id="Rascal108" Name="Rascal">
|
||||
<Component Id="_comp109" Guid="0bcd41b3-10cd-4623-af6c-5584a17bdba8">
|
||||
<Component Id="_comp109" Guid="298c761e-59ec-4f67-b2e9-cb0532e31ff5">
|
||||
<File Id="_110" Source="..\bin\release\aircraft\Rascal\Rascal-keyboard.xml" />
|
||||
<File Id="_111" Source="..\bin\release\aircraft\Rascal\Rascal-submodels.xml" />
|
||||
<File Id="_112" Source="..\bin\release\aircraft\Rascal\Rascal.xml" />
|
||||
@ -167,13 +167,13 @@
|
||||
<File Id="_118" Source="..\bin\release\aircraft\Rascal\thumbnail.jpg" />
|
||||
</Component>
|
||||
<Directory Id="Engines118" Name="Engines">
|
||||
<Component Id="_comp119" Guid="1b84e34a-3913-446e-b0a2-c9eb2df0bd8f">
|
||||
<Component Id="_comp119" Guid="9ea00190-d9e9-4241-8e46-43f4ab3e218c">
|
||||
<File Id="_120" Source="..\bin\release\aircraft\Rascal\Engines\18x8.xml" />
|
||||
<File Id="_121" Source="..\bin\release\aircraft\Rascal\Engines\Zenoah_G-26A.xml" />
|
||||
</Component>
|
||||
</Directory>
|
||||
<Directory Id="Models121" Name="Models">
|
||||
<Component Id="_comp122" Guid="b7b2111e-d900-4138-ba59-84b2b0d20312">
|
||||
<Component Id="_comp122" Guid="6f7543bb-4fdf-4753-9ca5-32060bfe1931">
|
||||
<File Id="_123" Source="..\bin\release\aircraft\Rascal\Models\Rascal.rgb" />
|
||||
<File Id="_124" Source="..\bin\release\aircraft\Rascal\Models\Rascal110-000-013.ac" />
|
||||
<File Id="_125" Source="..\bin\release\aircraft\Rascal\Models\Rascal110.xml" />
|
||||
@ -184,7 +184,7 @@
|
||||
</Component>
|
||||
</Directory>
|
||||
<Directory Id="Systems129" Name="Systems">
|
||||
<Component Id="_comp130" Guid="e9011402-edb8-4e71-a931-b3586e1957f1">
|
||||
<Component Id="_comp130" Guid="98eec223-3d58-493d-b3ca-86b87bf15b7b">
|
||||
<File Id="_131" Source="..\bin\release\aircraft\Rascal\Systems\110-autopilot.xml" />
|
||||
<File Id="_132" Source="..\bin\release\aircraft\Rascal\Systems\airdata.nas" />
|
||||
<File Id="_133" Source="..\bin\release\aircraft\Rascal\Systems\electrical.xml" />
|
||||
@ -195,33 +195,33 @@
|
||||
</Directory>
|
||||
</Directory>
|
||||
<Directory Id="Driver135" Name="Driver">
|
||||
<Component Id="_comp136" Guid="678ec7c2-bae0-4713-bd1b-128930c9c007">
|
||||
<Component Id="_comp136" Guid="726d716b-4f59-4279-b3b8-d3a4feedd955">
|
||||
<File Id="_137" Source="..\bin\release\Driver\Arduino MEGA 2560.inf" />
|
||||
</Component>
|
||||
</Directory>
|
||||
<Directory Id="es_ES137" Name="es-ES">
|
||||
<Component Id="_comp138" Guid="6df345fb-36a3-4487-9a6f-5590f9588881">
|
||||
<Component Id="_comp138" Guid="742f0915-4703-4fc2-83f0-b7d0a26818d1">
|
||||
<File Id="_139" Source="..\bin\release\es-ES\ArdupilotMegaPlanner10.resources.dll" />
|
||||
</Component>
|
||||
</Directory>
|
||||
<Directory Id="fr139" Name="fr">
|
||||
<Component Id="_comp140" Guid="365d4a44-fc28-4608-9930-2400444bac16">
|
||||
<Component Id="_comp140" Guid="338b72e0-a18c-416c-92b8-69258b7076b7">
|
||||
<File Id="_141" Source="..\bin\release\fr\ArdupilotMegaPlanner10.resources.dll" />
|
||||
</Component>
|
||||
</Directory>
|
||||
<Directory Id="it_IT141" Name="it-IT">
|
||||
<Component Id="_comp142" Guid="b1192a5c-0d15-4dd6-ab35-e62bc6d6a9d9">
|
||||
<Component Id="_comp142" Guid="e83b71ed-67c7-42c2-b8b5-588e8511c2ca">
|
||||
<File Id="_143" Source="..\bin\release\it-IT\ArdupilotMegaPlanner10.resources.dll" />
|
||||
</Component>
|
||||
</Directory>
|
||||
<Directory Id="jsbsim143" Name="jsbsim">
|
||||
<Component Id="_comp144" Guid="73b6499b-4203-430f-9c95-da9e0db49c20">
|
||||
<Component Id="_comp144" Guid="70619133-00c7-4e8e-ba27-d95e45e59174">
|
||||
<File Id="_145" Source="..\bin\release\jsbsim\fgout.xml" />
|
||||
<File Id="_146" Source="..\bin\release\jsbsim\rascal_test.xml" />
|
||||
</Component>
|
||||
</Directory>
|
||||
<Directory Id="m3u146" Name="m3u">
|
||||
<Component Id="_comp147" Guid="932891e2-4e2c-4b84-806b-c5ec48c2ac4b">
|
||||
<Component Id="_comp147" Guid="09d6c520-34e5-4320-8696-158b122b4ef9">
|
||||
<File Id="_148" Source="..\bin\release\m3u\both.m3u" />
|
||||
<File Id="_149" Source="..\bin\release\m3u\GeoRefnetworklink.kml" />
|
||||
<File Id="_150" Source="..\bin\release\m3u\hud.m3u" />
|
||||
@ -230,28 +230,28 @@
|
||||
</Component>
|
||||
</Directory>
|
||||
<Directory Id="pl152" Name="pl">
|
||||
<Component Id="_comp153" Guid="d1e70fe8-8ab8-437d-aa0b-a2e20d184239">
|
||||
<Component Id="_comp153" Guid="a18e7331-9eec-40a5-a159-242c4b94f34e">
|
||||
<File Id="_154" Source="..\bin\release\pl\ArdupilotMegaPlanner10.resources.dll" />
|
||||
</Component>
|
||||
</Directory>
|
||||
<Directory Id="Resources154" Name="Resources">
|
||||
<Component Id="_comp155" Guid="ed6bee2f-a466-4369-97e9-80d538f04460">
|
||||
<Component Id="_comp155" Guid="6bdbafb9-758f-4d9c-a05d-c141444e2606">
|
||||
<File Id="_156" Source="..\bin\release\Resources\MAVCmd.txt" />
|
||||
<File Id="_157" Source="..\bin\release\Resources\Welcome_to_Michael_Oborne.rtf" />
|
||||
</Component>
|
||||
</Directory>
|
||||
<Directory Id="ru_RU157" Name="ru-RU">
|
||||
<Component Id="_comp158" Guid="024f81d4-35cf-4a2c-82b4-025dcdefab19">
|
||||
<Component Id="_comp158" Guid="c9e58446-bf33-4d06-82f4-9288c71a3a23">
|
||||
<File Id="_159" Source="..\bin\release\ru-RU\ArdupilotMegaPlanner10.resources.dll" />
|
||||
</Component>
|
||||
</Directory>
|
||||
<Directory Id="zh_Hans159" Name="zh-Hans">
|
||||
<Component Id="_comp160" Guid="f8f2b516-9e24-4532-8a8f-76b2bd21d431">
|
||||
<Component Id="_comp160" Guid="d4d2dfdd-1669-4db9-9206-c7b31ca54a37">
|
||||
<File Id="_161" Source="..\bin\release\zh-Hans\ArdupilotMegaPlanner10.resources.dll" />
|
||||
</Component>
|
||||
</Directory>
|
||||
<Directory Id="zh_TW161" Name="zh-TW">
|
||||
<Component Id="_comp162" Guid="892671df-1ce2-40ba-ba99-2b777c4815bd">
|
||||
<Component Id="_comp162" Guid="29650cfa-23a1-4c74-b963-877104b50f78">
|
||||
<File Id="_163" Source="..\bin\release\zh-TW\ArdupilotMegaPlanner10.resources.dll" />
|
||||
</Component>
|
||||
</Directory>
|
||||
|
@ -67,11 +67,11 @@ namespace ArdupilotMega
|
||||
{
|
||||
Thread.CurrentThread.Name = "Base Thread";
|
||||
|
||||
Application.Run(new MainV2());
|
||||
Application.Run(new MainV2());
|
||||
}
|
||||
catch (Exception ex)
|
||||
{
|
||||
log.Fatal("Fatal app exception",ex);
|
||||
log.Fatal("Fatal app exception", ex);
|
||||
Console.WriteLine(ex.ToString());
|
||||
|
||||
Console.ReadLine();
|
||||
@ -99,10 +99,12 @@ namespace ArdupilotMega
|
||||
|
||||
log.Debug(ex.ToString());
|
||||
|
||||
if (ex.Message == "Requested registry access is not allowed.") {
|
||||
if (ex.Message == "Requested registry access is not allowed.")
|
||||
{
|
||||
return;
|
||||
}
|
||||
if (ex.Message == "The port is closed.") {
|
||||
if (ex.Message == "The port is closed.")
|
||||
{
|
||||
CustomMessageBox.Show("Serial connection has been lost");
|
||||
return;
|
||||
}
|
||||
@ -122,10 +124,10 @@ namespace ArdupilotMega
|
||||
}
|
||||
if (e.Exception.GetType() == typeof(FileNotFoundException) || e.Exception.GetType() == typeof(BadImageFormatException)) // i get alot of error from people who click the exe from inside a zip file.
|
||||
{
|
||||
CustomMessageBox.Show("You are missing some DLL's. Please extract the zip file somewhere. OR Use the update feature from the menu " + e.Exception.ToString() );
|
||||
// return;
|
||||
CustomMessageBox.Show("You are missing some DLL's. Please extract the zip file somewhere. OR Use the update feature from the menu " + e.Exception.ToString());
|
||||
// return;
|
||||
}
|
||||
DialogResult dr = CustomMessageBox.Show("An error has occurred\n"+ex.ToString() + "\n\nReport this Error???", "Send Error", MessageBoxButtons.YesNo);
|
||||
DialogResult dr = CustomMessageBox.Show("An error has occurred\n" + ex.ToString() + "\n\nReport this Error???", "Send Error", MessageBoxButtons.YesNo);
|
||||
if (DialogResult.Yes == dr)
|
||||
{
|
||||
try
|
||||
@ -172,4 +174,4 @@ namespace ArdupilotMega
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
@ -34,5 +34,5 @@ using System.Resources;
|
||||
// by using the '*' as shown below:
|
||||
// [assembly: AssemblyVersion("1.0.*")]
|
||||
[assembly: AssemblyVersion("1.1.*")]
|
||||
[assembly: AssemblyFileVersion("1.2.6")]
|
||||
[assembly: AssemblyFileVersion("1.2.7")]
|
||||
[assembly: NeutralResourcesLanguageAttribute("")]
|
||||
|
Loading…
Reference in New Issue
Block a user