APM Planner 1.0.69

prep for ac2 2.0.43 - simple mode
modify some scaling in Config
add hud speed warning. add link quality and time to HUD
fix ac2 logs, relative alt.
prep for mavlink 1.0
add time to tlog > plain text conversion
This commit is contained in:
Michael Oborne 2011-09-17 21:22:07 +08:00
parent 19781d5e4a
commit 39640e8d94
27 changed files with 16161 additions and 13088 deletions

View File

@ -188,6 +188,7 @@
<SubType>Component</SubType>
</Compile>
<Compile Include="CommsUdpSerial.cs" />
<Compile Include="georefimage.cs" />
<Compile Include="HIL\Aircraft.cs" />
<Compile Include="HIL\Point3d.cs" />
<Compile Include="HIL\QuadCopter.cs" />

View File

@ -240,13 +240,12 @@ namespace ArdupilotMega
{
STABILIZE = 0, // hold level position
ACRO = 1, // rate control
SIMPLE = 2, //
ALT_HOLD = 3, // AUTO control
AUTO = 4, // AUTO control
GUIDED = 5, // AUTO control
LOITER = 6, // Hold a single location
RTL = 7, // AUTO control
CIRCLE = 8
ALT_HOLD = 2, // AUTO control
AUTO = 3, // AUTO control
GUIDED = 4, // AUTO control
LOITER = 5, // Hold a single location
RTL = 6, // AUTO control
CIRCLE = 7
}
public static bool translateMode(string modein, ref MAVLink.__mavlink_set_nav_mode_t navmode, ref MAVLink.__mavlink_set_mode_t mode)

View File

@ -65,7 +65,7 @@ namespace ArdupilotMega
public float gz { get; set; }
// calced turn rate
public float turnrate { get { if (groundspeed == 0) return 0; return (roll * 9.8f) / groundspeed; } }
public float turnrate { get { if (groundspeed <= 1) return 0; return (roll * 9.8f) / groundspeed; } }
//radio
public float ch1in { get; set; }
@ -101,17 +101,17 @@ namespace ArdupilotMega
//nav state
public float nav_roll { get; set; }
public float nav_pitch { get; set; }
public short nav_bearing { get; set; }
public short target_bearing { get; set; }
public ushort wp_dist { get { return (ushort)(_wpdist * multiplierdist); } set { _wpdist = value; } }
public float nav_bearing { get; set; }
public float target_bearing { get; set; }
public float wp_dist { get { return (_wpdist * multiplierdist); } set { _wpdist = value; } }
public float alt_error { get { return _alt_error * multiplierdist; } set { _alt_error = value; } }
public float ber_error { get { return (target_bearing - yaw); } set { } }
public float aspd_error { get { return _aspd_error * multiplierspeed; } set { _aspd_error = value; } }
public float xtrack_error { get; set; }
public int wpno { get; set; }
public float wpno { get; set; }
public string mode { get; set; }
public float climbrate { get; set; }
ushort _wpdist;
float _wpdist;
float _aspd_error;
float _alt_error;
@ -150,7 +150,8 @@ namespace ArdupilotMega
public float brklevel { get; set; }
// stats
public ushort packetdrop { get; set; }
public ushort packetdropremote { get; set; }
public ushort linkqualitygcs { get; set; }
// requested stream rates
public byte rateattitude { get; set; }
@ -361,7 +362,7 @@ namespace ArdupilotMega
battery_voltage = sysstatus.vbat;
battery_remaining = sysstatus.battery_remaining;
packetdrop = sysstatus.packet_drop;
packetdropremote = sysstatus.packet_drop;
if (oldmode != mode && MainV2.speechenable && MainV2.getConfig("speechmodeenabled") == "True")
{
@ -468,7 +469,7 @@ namespace ArdupilotMega
wpcur = (ArdupilotMega.MAVLink.__mavlink_waypoint_current_t)(temp);
int oldwp = wpno;
int oldwp = (int)wpno;
wpno = wpcur.seq;

View File

@ -30,8 +30,8 @@
{
this.components = new System.ComponentModel.Container();
System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(Configuration));
System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle3 = new System.Windows.Forms.DataGridViewCellStyle();
System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle4 = new System.Windows.Forms.DataGridViewCellStyle();
System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle1 = new System.Windows.Forms.DataGridViewCellStyle();
System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle2 = new System.Windows.Forms.DataGridViewCellStyle();
this.Params = new System.Windows.Forms.DataGridView();
this.Command = new System.Windows.Forms.DataGridViewTextBoxColumn();
this.Value = new System.Windows.Forms.DataGridViewTextBoxColumn();
@ -167,9 +167,6 @@
this.label21 = new System.Windows.Forms.Label();
this.THR_HOLD_P = new System.Windows.Forms.DomainUpDown();
this.label22 = new System.Windows.Forms.Label();
this.groupBox18 = new System.Windows.Forms.GroupBox();
this.PITCH_MAX = new System.Windows.Forms.DomainUpDown();
this.label27 = new System.Windows.Forms.Label();
this.groupBox19 = new System.Windows.Forms.GroupBox();
this.HLD_LAT_IMAX = new System.Windows.Forms.DomainUpDown();
this.label28 = new System.Windows.Forms.Label();
@ -285,7 +282,6 @@
this.groupBox4.SuspendLayout();
this.groupBox6.SuspendLayout();
this.groupBox7.SuspendLayout();
this.groupBox18.SuspendLayout();
this.groupBox19.SuspendLayout();
this.groupBox20.SuspendLayout();
this.groupBox21.SuspendLayout();
@ -302,14 +298,14 @@
this.Params.AllowUserToAddRows = false;
this.Params.AllowUserToDeleteRows = false;
resources.ApplyResources(this.Params, "Params");
dataGridViewCellStyle3.Alignment = System.Windows.Forms.DataGridViewContentAlignment.MiddleLeft;
dataGridViewCellStyle3.BackColor = System.Drawing.Color.Maroon;
dataGridViewCellStyle3.Font = new System.Drawing.Font("Microsoft Sans Serif", 8.25F, System.Drawing.FontStyle.Regular, System.Drawing.GraphicsUnit.Point, ((byte)(0)));
dataGridViewCellStyle3.ForeColor = System.Drawing.Color.White;
dataGridViewCellStyle3.SelectionBackColor = System.Drawing.SystemColors.Highlight;
dataGridViewCellStyle3.SelectionForeColor = System.Drawing.SystemColors.HighlightText;
dataGridViewCellStyle3.WrapMode = System.Windows.Forms.DataGridViewTriState.True;
this.Params.ColumnHeadersDefaultCellStyle = dataGridViewCellStyle3;
dataGridViewCellStyle1.Alignment = System.Windows.Forms.DataGridViewContentAlignment.MiddleLeft;
dataGridViewCellStyle1.BackColor = System.Drawing.Color.Maroon;
dataGridViewCellStyle1.Font = new System.Drawing.Font("Microsoft Sans Serif", 8.25F, System.Drawing.FontStyle.Regular, System.Drawing.GraphicsUnit.Point, ((byte)(0)));
dataGridViewCellStyle1.ForeColor = System.Drawing.Color.White;
dataGridViewCellStyle1.SelectionBackColor = System.Drawing.SystemColors.Highlight;
dataGridViewCellStyle1.SelectionForeColor = System.Drawing.SystemColors.HighlightText;
dataGridViewCellStyle1.WrapMode = System.Windows.Forms.DataGridViewTriState.True;
this.Params.ColumnHeadersDefaultCellStyle = dataGridViewCellStyle1;
this.Params.ColumnHeadersHeightSizeMode = System.Windows.Forms.DataGridViewColumnHeadersHeightSizeMode.AutoSize;
this.Params.Columns.AddRange(new System.Windows.Forms.DataGridViewColumn[] {
this.Command,
@ -318,14 +314,14 @@
this.mavScale,
this.RawValue});
this.Params.Name = "Params";
dataGridViewCellStyle4.Alignment = System.Windows.Forms.DataGridViewContentAlignment.MiddleLeft;
dataGridViewCellStyle4.BackColor = System.Drawing.SystemColors.ActiveCaption;
dataGridViewCellStyle4.Font = new System.Drawing.Font("Microsoft Sans Serif", 8.25F, System.Drawing.FontStyle.Regular, System.Drawing.GraphicsUnit.Point, ((byte)(0)));
dataGridViewCellStyle4.ForeColor = System.Drawing.SystemColors.WindowText;
dataGridViewCellStyle4.SelectionBackColor = System.Drawing.SystemColors.Highlight;
dataGridViewCellStyle4.SelectionForeColor = System.Drawing.SystemColors.HighlightText;
dataGridViewCellStyle4.WrapMode = System.Windows.Forms.DataGridViewTriState.True;
this.Params.RowHeadersDefaultCellStyle = dataGridViewCellStyle4;
dataGridViewCellStyle2.Alignment = System.Windows.Forms.DataGridViewContentAlignment.MiddleLeft;
dataGridViewCellStyle2.BackColor = System.Drawing.SystemColors.ActiveCaption;
dataGridViewCellStyle2.Font = new System.Drawing.Font("Microsoft Sans Serif", 8.25F, System.Drawing.FontStyle.Regular, System.Drawing.GraphicsUnit.Point, ((byte)(0)));
dataGridViewCellStyle2.ForeColor = System.Drawing.SystemColors.WindowText;
dataGridViewCellStyle2.SelectionBackColor = System.Drawing.SystemColors.Highlight;
dataGridViewCellStyle2.SelectionForeColor = System.Drawing.SystemColors.HighlightText;
dataGridViewCellStyle2.WrapMode = System.Windows.Forms.DataGridViewTriState.True;
this.Params.RowHeadersDefaultCellStyle = dataGridViewCellStyle2;
this.Params.RowHeadersVisible = false;
this.Params.CellValueChanged += new System.Windows.Forms.DataGridViewCellEventHandler(this.Params_CellValueChanged);
//
@ -990,7 +986,6 @@
this.TabAC2.Controls.Add(this.groupBox4);
this.TabAC2.Controls.Add(this.groupBox6);
this.TabAC2.Controls.Add(this.groupBox7);
this.TabAC2.Controls.Add(this.groupBox18);
this.TabAC2.Controls.Add(this.groupBox19);
this.TabAC2.Controls.Add(this.groupBox20);
this.TabAC2.Controls.Add(this.groupBox21);
@ -1157,24 +1152,6 @@
resources.ApplyResources(this.label22, "label22");
this.label22.Name = "label22";
//
// groupBox18
//
this.groupBox18.Controls.Add(this.PITCH_MAX);
this.groupBox18.Controls.Add(this.label27);
resources.ApplyResources(this.groupBox18, "groupBox18");
this.groupBox18.Name = "groupBox18";
this.groupBox18.TabStop = false;
//
// PITCH_MAX
//
resources.ApplyResources(this.PITCH_MAX, "PITCH_MAX");
this.PITCH_MAX.Name = "PITCH_MAX";
//
// label27
//
resources.ApplyResources(this.label27, "label27");
this.label27.Name = "label27";
//
// groupBox19
//
this.groupBox19.Controls.Add(this.HLD_LAT_IMAX);
@ -1887,7 +1864,6 @@
this.groupBox4.ResumeLayout(false);
this.groupBox6.ResumeLayout(false);
this.groupBox7.ResumeLayout(false);
this.groupBox18.ResumeLayout(false);
this.groupBox19.ResumeLayout(false);
this.groupBox20.ResumeLayout(false);
this.groupBox21.ResumeLayout(false);
@ -2031,9 +2007,6 @@
private System.Windows.Forms.Label label21;
private System.Windows.Forms.DomainUpDown THR_HOLD_P;
private System.Windows.Forms.Label label22;
private System.Windows.Forms.GroupBox groupBox18;
private System.Windows.Forms.DomainUpDown PITCH_MAX;
private System.Windows.Forms.Label label27;
private System.Windows.Forms.GroupBox groupBox19;
private System.Windows.Forms.DomainUpDown HLD_LAT_IMAX;
private System.Windows.Forms.Label label28;

File diff suppressed because it is too large Load Diff

View File

@ -436,10 +436,13 @@ namespace ArdupilotMega.GCSViews
{
this.BeginInvoke((MethodInvoker)delegate()
{
tracklog.Value = (int)(MainV2.comPort.logplaybackfile.BaseStream.Position / (double)MainV2.comPort.logplaybackfile.BaseStream.Length * 100);
lbl_logpercent.Text = (MainV2.comPort.logplaybackfile.BaseStream.Position / (double)MainV2.comPort.logplaybackfile.BaseStream.Length).ToString("0.00%");
try
{
tracklog.Value = (int)(MainV2.comPort.logplaybackfile.BaseStream.Position / (double)MainV2.comPort.logplaybackfile.BaseStream.Length * 100);
lbl_logpercent.Text = (MainV2.comPort.logplaybackfile.BaseStream.Position / (double)MainV2.comPort.logplaybackfile.BaseStream.Length).ToString("0.00%");
}
catch { }
});
}
@ -861,6 +864,8 @@ namespace ArdupilotMega.GCSViews
if (MainV2.comPort.logplaybackfile != null)
MainV2.comPort.logplaybackfile.BaseStream.Position = (long)(MainV2.comPort.logplaybackfile.BaseStream.Length * (tracklog.Value / 100.0));
updateLogPlayPosition();
}
bool loaded = false;
@ -1223,7 +1228,7 @@ namespace ArdupilotMega.GCSViews
// Get the TypeCode enumeration. Multiple types get mapped to a common typecode.
TypeCode typeCode = Type.GetTypeCode(fieldValue.GetType());
if (!(typeCode == TypeCode.Single || typeCode == TypeCode.Double || typeCode == TypeCode.Int32))
if (!(typeCode == TypeCode.Single))
continue;
CheckBox chk_box = new CheckBox();

View File

@ -1228,7 +1228,7 @@ namespace ArdupilotMega.GCSViews
if (CHK_holdalt.Checked)
{
port.setParam("ALT_HOLD_RTL", int.Parse(TXT_DefaultAlt.Text) / MainV2.cs.multiplierdist * 100);
port.setParam("ALT_HOLD_RTL", int.Parse(TXT_DefaultAlt.Text) / MainV2.cs.multiplierdist);
}
else
{
@ -1360,7 +1360,7 @@ namespace ArdupilotMega.GCSViews
}
}
TXT_DefaultAlt.Text = ((float)param["ALT_HOLD_RTL"] * MainV2.cs.multiplierdist / 100).ToString("0");
TXT_DefaultAlt.Text = ((float)param["ALT_HOLD_RTL"] * MainV2.cs.multiplierdist).ToString("0");
TXT_WPRad.Text = ((float)param["WP_RADIUS"] * MainV2.cs.multiplierdist).ToString("0");
try
{

View File

@ -23,7 +23,7 @@ using OpenTK.Graphics;
namespace hud
{
public partial class HUD : GLControl
public class HUD : GLControl// : Graphics
{
object paintlock = new object();
object streamlock = new object();
@ -38,7 +38,9 @@ namespace hud
int[] charbitmaptexid = new int[6000];
int[] charwidth = new int[6000];
int huddrawtime = 0;
public int huddrawtime = 0;
public bool opengl = true;
public HUD()
{
@ -46,7 +48,7 @@ namespace hud
return;
InitializeComponent();
graphicsObject = this;
//graphicsObject = this;
//graphicsObject = Graphics.FromImage(objBitmap);
}
@ -150,7 +152,6 @@ System.ComponentModel.Category("Values")]
Bitmap objBitmap = new Bitmap(1024, 1024);
int count = 0;
DateTime countdate = DateTime.Now;
HUD graphicsObject; // Graphics
DateTime starttime = DateTime.MinValue;
@ -225,14 +226,14 @@ System.ComponentModel.Category("Values")]
{
//GL.Enable(EnableCap.AlphaTest);
if (this.DesignMode)
{
e.Graphics.Clear(this.BackColor);
e.Graphics.Flush();
return;
if (this.DesignMode)
{
e.Graphics.Clear(this.BackColor);
e.Graphics.Flush();
return;
}
if ((DateTime.Now - starttime).TotalMilliseconds < 75 && (_bgimage == null))
if ((DateTime.Now - starttime).TotalMilliseconds < 75 && (_bgimage == null))
{
//Console.WriteLine("ms "+(DateTime.Now - starttime).TotalMilliseconds);
//e.Graphics.DrawImageUnscaled(objBitmap, 0, 0);
@ -241,35 +242,40 @@ System.ComponentModel.Category("Values")]
starttime = DateTime.Now;
//Console.WriteLine(DateTime.Now.Millisecond);
if (Console.CursorLeft > 0)
{
//Console.WriteLine(" "+ Console.CursorLeft +" ");
}
//Console.Write("HUD a "+(DateTime.Now - starttime).TotalMilliseconds);
MakeCurrent();
//GL.LoadIdentity();
//GL.ClearColor(Color.Red);
//Console.Write(" b " + (DateTime.Now - starttime).TotalMilliseconds);
GL.Clear(ClearBufferMask.ColorBufferBit);
//GL.LoadIdentity();
//Console.Write(" c " + (DateTime.Now - starttime).TotalMilliseconds);
//GL.Viewport(0, 0, Width, Height);
doPaint(e);
doPaint();
//Console.Write(" d " + (DateTime.Now - starttime).TotalMilliseconds);
this.SwapBuffers();
//Console.Write(" e " + (DateTime.Now - starttime).TotalMilliseconds);
count++;
huddrawtime += (int)(DateTime.Now - starttime).TotalMilliseconds;
if (DateTime.Now.Second != countdate.Second)
{
countdate = DateTime.Now;
Console.WriteLine("HUD " + count + " hz drawtime " + huddrawtime);
Console.WriteLine("HUD " + count + " hz drawtime " + (huddrawtime / count));
count = 0;
huddrawtime = 0;
}
huddrawtime = (int)(DateTime.Now - starttime).TotalMilliseconds;
#if DEBUG
//Console.WriteLine("HUD e " + (DateTime.Now - starttime).TotalMilliseconds + " " + DateTime.Now.Millisecond);
#endif
}
void Clear(Color color)
@ -282,7 +288,7 @@ System.ComponentModel.Category("Values")]
//graphicsObject.DrawArc(whitePen, arcrect, 180 + 45, 90);
void DrawArc(Pen penn,RectangleF rect, float start,float degrees)
public void DrawArc(Pen penn,RectangleF rect, float start,float degrees)
{
//GL.Disable(EnableCap.Texture2D);
@ -309,7 +315,7 @@ System.ComponentModel.Category("Values")]
//GL.Enable(EnableCap.Texture2D);
}
void DrawEllipse(Pen penn, Rectangle rect)
public void DrawEllipse(Pen penn, Rectangle rect)
{
//GL.Disable(EnableCap.Texture2D);
@ -340,7 +346,7 @@ System.ComponentModel.Category("Values")]
int texture;
Bitmap bitmap = new Bitmap(512,512);
void DrawImage(Image img, int x, int y, int width, int height)
public void DrawImage(Image img, int x, int y, int width, int height)
{
if (img == null)
return;
@ -392,7 +398,7 @@ System.ComponentModel.Category("Values")]
GL.Disable(EnableCap.Texture2D);
}
void DrawPath(Pen penn,GraphicsPath gp)
public void DrawPath(Pen penn, GraphicsPath gp)
{
try
{
@ -401,7 +407,7 @@ System.ComponentModel.Category("Values")]
catch { }
}
void FillPath(Brush brushh,GraphicsPath gp)
public void FillPath(Brush brushh, GraphicsPath gp)
{
try
{
@ -410,32 +416,32 @@ System.ComponentModel.Category("Values")]
catch { }
}
void SetClip(Rectangle rect)
public void SetClip(Rectangle rect)
{
}
void ResetClip()
public void ResetClip()
{
}
void ResetTransform()
public void ResetTransform()
{
GL.LoadIdentity();
}
void RotateTransform(float angle)
public void RotateTransform(float angle)
{
GL.Rotate(angle,0,0,1);
}
void TranslateTransform(float x, float y)
public void TranslateTransform(float x, float y)
{
GL.Translate(x, y, 0f);
}
void FillPolygon(Brush brushh, Point[] list)
public void FillPolygon(Brush brushh, Point[] list)
{
//GL.Disable(EnableCap.Texture2D);
@ -456,7 +462,7 @@ System.ComponentModel.Category("Values")]
//GL.Enable(EnableCap.Texture2D);
}
void FillPolygon(Brush brushh, PointF[] list)
public void FillPolygon(Brush brushh, PointF[] list)
{
//GL.Disable(EnableCap.Texture2D);
@ -478,7 +484,7 @@ System.ComponentModel.Category("Values")]
//graphicsObject.DrawPolygon(redPen, pointlist);
void DrawPolygon(Pen penn, Point[] list)
public void DrawPolygon(Pen penn, Point[] list)
{
//GL.Disable(EnableCap.Texture2D);
@ -499,7 +505,7 @@ System.ComponentModel.Category("Values")]
//GL.Enable(EnableCap.Texture2D);
}
void DrawPolygon(Pen penn, PointF[] list)
public void DrawPolygon(Pen penn, PointF[] list)
{
//GL.Disable(EnableCap.Texture2D);
@ -523,7 +529,7 @@ System.ComponentModel.Category("Values")]
//graphicsObject.FillRectangle(linearBrush, bg);
void FillRectangle(Brush brushh,RectangleF rectf)
public void FillRectangle(Brush brushh, RectangleF rectf)
{
float x1 = rectf.X;
float y1 = rectf.Y;
@ -571,12 +577,12 @@ System.ComponentModel.Category("Values")]
//graphicsObject.DrawRectangle(transPen, bg.X,bg.Y,bg.Width,bg.Height);
void DrawRectangle(Pen penn, RectangleF rect)
public void DrawRectangle(Pen penn, RectangleF rect)
{
DrawRectangle(penn, rect.X, rect.Y, rect.Width, rect.Height);
}
void DrawRectangle(Pen penn,double x1,double y1, double width,double height)
public void DrawRectangle(Pen penn, double x1, double y1, double width, double height)
{
//GL.Disable(EnableCap.Texture2D);
@ -597,7 +603,7 @@ System.ComponentModel.Category("Values")]
//GL.Enable(EnableCap.Texture2D);
}
void DrawLine(Pen penn,double x1,double y1, double x2,double y2)
public void DrawLine(Pen penn, double x1, double y1, double x2, double y2)
{
//GL.Disable(EnableCap.Texture2D);
@ -616,8 +622,13 @@ System.ComponentModel.Category("Values")]
//GL.Enable(EnableCap.Texture2D);
}
void doPaint()
void doPaint(object e)
{
HUD graphicsObject = this;
//Graphics graphicsObject = ((PaintEventArgs)e).Graphics;
//graphicsObject.SmoothingMode = SmoothingMode.AntiAlias;
try
{
graphicsObject.Clear(Color.Gray);
@ -1131,6 +1142,20 @@ System.ComponentModel.Category("Values")]
drawstring(graphicsObject, mode, font, fontsize, whiteBrush, scrollbg.Left - 30, scrollbg.Bottom + 5);
drawstring(graphicsObject, (int)disttowp + ">" + wpno, font, fontsize, whiteBrush, scrollbg.Left - 30, scrollbg.Bottom + fontsize + 2 + 10);
graphicsObject.DrawLine(greenPen, scrollbg.Left - 5, scrollbg.Top - (int)(fontsize * 2.2) - 2 - 20, scrollbg.Left - 5, scrollbg.Top - (int)(fontsize) - 2 - 20);
graphicsObject.DrawLine(greenPen, scrollbg.Left - 10, scrollbg.Top - (int)(fontsize * 2.2) - 2 - 15, scrollbg.Left - 10, scrollbg.Top - (int)(fontsize) - 2 - 20);
graphicsObject.DrawLine(greenPen, scrollbg.Left - 15, scrollbg.Top - (int)(fontsize * 2.2) - 2 - 10, scrollbg.Left - 15, scrollbg.Top - (int)(fontsize ) - 2 - 20);
drawstring(graphicsObject, ArdupilotMega.MainV2.cs.linkqualitygcs.ToString("0") + "%", font, fontsize, whiteBrush, scrollbg.Left, scrollbg.Top - (int)(fontsize * 2.2) - 2 - 20);
if (ArdupilotMega.MainV2.cs.linkqualitygcs == 0)
{
graphicsObject.DrawLine(redPen, scrollbg.Left, scrollbg.Top - (int)(fontsize * 2.2) - 2 - 20, scrollbg.Left + 50, scrollbg.Top - (int)(fontsize * 2.2) - 2);
graphicsObject.DrawLine(redPen, scrollbg.Left, scrollbg.Top - (int)(fontsize * 2.2) - 2, scrollbg.Left + 50, scrollbg.Top - (int)(fontsize * 2.2) - 2 - 20);
}
drawstring(graphicsObject, ArdupilotMega.MainV2.cs.datetime.ToString("HH:mm:ss"), font, fontsize, whiteBrush, scrollbg.Left - 20, scrollbg.Top - fontsize - 2 - 20);
// battery
graphicsObject.ResetTransform();
@ -1191,8 +1216,6 @@ System.ComponentModel.Category("Values")]
Console.WriteLine("hud error "+ex.ToString());
//MessageBox.Show(ex.ToString());
}
count++;
}
protected override void OnPaintBackground(PaintEventArgs e)
@ -1355,6 +1378,31 @@ System.ComponentModel.Category("Values")]
x += charwidth[charid] * scale;
}
}
void drawstring(Graphics e, string text, Font font, float fontsize, Brush brush, float x, float y)
{
if (text == null || text == "")
return;
pth.Reset();
if (text != null)
pth.AddString(text, font.FontFamily, 0, fontsize + 5, new Point((int)x, (int)y), StringFormat.GenericTypographic);
//Draw the edge
// this uses lots of cpu time
//e.SmoothingMode = SmoothingMode.HighSpeed;
e.DrawPath(P, pth);
//Draw the face
e.FillPath(brush, pth);
//pth.Dispose();
}
protected override void OnResize(EventArgs e)
{

View File

@ -375,6 +375,13 @@ namespace ArdupilotMega
{
Color[] colours = { Color.Red, Color.Orange, Color.Yellow, Color.Green, Color.Blue, Color.Indigo, Color.Violet, Color.Pink };
AltitudeMode altmode = AltitudeMode.absolute;
if (MainV2.cs.firmware == MainV2.Firmwares.ArduCopter2)
{
altmode = AltitudeMode.relativeToGround; // because of sonar, this is both right and wrong. right for sonar, wrong in terms of gps as the land slopes off.
}
KMLRoot kml = new KMLRoot();
Folder fldr = new Folder("Log");
@ -397,7 +404,7 @@ namespace ArdupilotMega
continue;
LineString ls = new LineString();
ls.AltitudeMode = AltitudeMode.absolute;
ls.AltitudeMode = altmode;
ls.Extrude = true;
//ls.Tessellate = true;
@ -484,7 +491,7 @@ namespace ArdupilotMega
pmplane.visibility = false;
Model model = mod.model;
model.AltitudeMode = AltitudeMode.absolute;
model.AltitudeMode = altmode;
model.Scale.x = 2;
model.Scale.y = 2;
model.Scale.z = 2;
@ -506,7 +513,7 @@ namespace ArdupilotMega
catch { }
pmplane.Point = new KmlPoint((float)model.Location.longitude, (float)model.Location.latitude, (float)model.Location.altitude);
pmplane.Point.AltitudeMode = AltitudeMode.absolute;
pmplane.Point.AltitudeMode = altmode;
Link link = new Link();
link.href = "block_plane_0.dae";

View File

@ -16,6 +16,9 @@ namespace ArdupilotMega
{
public ICommsSerial BaseStream = new SerialPort();
/// <summary>
/// used for outbound packet sending
/// </summary>
byte packetcount = 0;
public byte sysid = 0;
public byte compid = 0;
@ -29,6 +32,8 @@ namespace ArdupilotMega
public DateTime lastvalidpacket = DateTime.Now;
bool oldlogformat = false;
byte mavlinkversion = 0;
public PointLatLngAlt[] wps = new PointLatLngAlt[200];
public bool debugmavlink = false;
@ -45,7 +50,12 @@ namespace ArdupilotMega
public int bps = 0;
public DateTime bpstime = DateTime.Now;
int recvpacketcount = 0;
int packetslost = 0;
float synclost;
float packetslost = 0;
float packetsnotlost = 0;
DateTime packetlosttimer = DateTime.Now;
//Stopwatch stopwatch = new Stopwatch();
@ -169,15 +179,25 @@ namespace ArdupilotMega
if (buffer.Length > 5 && buffer1.Length > 5 && buffer[3] == buffer1[3] && buffer[4] == buffer1[4])
{
__mavlink_heartbeat_t hb = new __mavlink_heartbeat_t();
object temp = hb;
MAVLink.ByteArrayToStructure(buffer, ref temp, 6);
hb = (MAVLink.__mavlink_heartbeat_t)(temp);
mavlinkversion = hb.mavlink_version;
sysid = buffer[3];
compid = buffer[4];
recvpacketcount = buffer[2];
Console.WriteLine("ID " + sysid + " " + compid);
Console.WriteLine("ID sys " + sysid + " comp " + compid + " ver" + mavlinkversion);
break;
}
}
frm.Controls[0].Text = "Getting Params.. (sysid " + sysid + ") ";
frm.Controls[0].Text = "Getting Params.. (sysid " + sysid + " compid "+compid+") ";
frm.Refresh();
if (getparams == true)
getParamList();
@ -331,12 +351,28 @@ namespace ArdupilotMega
/// <param name="indata">struct of data</param>
public void generatePacket(byte messageType, object indata)
{
byte[] data = StructureToByteArrayEndian(indata);
byte[] data;
if (mavlinkversion == 3)
{
data = StructureToByteArray(indata);
}
else
{
data = StructureToByteArrayEndian(indata);
}
//Console.WriteLine(DateTime.Now + " PC Doing req "+ messageType + " " + this.BytesToRead);
byte[] packet = new byte[data.Length + 6 + 2];
packet[0] = (byte)'U';
if (mavlinkversion == 3)
{
packet[0] = 254;
}
else if (mavlinkversion == 2)
{
packet[0] = (byte)'U';
}
packet[1] = (byte)data.Length;
packet[2] = packetcount;
packet[3] = 255; // this is always 255 - MYGCS
@ -351,6 +387,12 @@ namespace ArdupilotMega
}
ushort checksum = crc_calculate(packet, packet[1] + 6);
if (mavlinkversion == 3)
{
checksum = crc_accumulate(MAVLINK_MESSAGE_CRCS[messageType], checksum);
}
byte ck_a = (byte)(checksum & 0xFF); ///< High byte
byte ck_b = (byte)(checksum >> 8); ///< Low byte
@ -425,6 +467,8 @@ namespace ArdupilotMega
byte[] temp = ASCIIEncoding.ASCII.GetBytes(paramname);
modifyParamForDisplay(false, paramname, ref value);
Array.Resize(ref temp, 15);
req.param_id = temp;
@ -458,7 +502,31 @@ namespace ArdupilotMega
{
if (buffer[5] == MAVLINK_MSG_ID_PARAM_VALUE)
{
param[paramname] = req.param_value;
__mavlink_param_value_t par = new __mavlink_param_value_t();
object tempobj = par;
ByteArrayToStructure(buffer, ref tempobj, 6);
par = (__mavlink_param_value_t)tempobj;
string st = System.Text.ASCIIEncoding.ASCII.GetString(par.param_id);
int pos = st.IndexOf('\0');
if (pos != -1)
{
st = st.Substring(0, pos);
}
if (st != paramname)
{
Console.WriteLine("MAVLINK bad param responce - {0} vs {1}",paramname,st);
continue;
}
param[st] = (par.param_value);
MainV2.givecomport = false;
//System.Threading.Thread.Sleep(100);//(int)(8.5 * 5)); // 8.5ms per byte
return true;
@ -559,6 +627,8 @@ namespace ArdupilotMega
st = st.Substring(0, pos);
}
modifyParamForDisplay(true, st, ref par.param_value);
param[st] = (par.param_value);
a++;
@ -575,17 +645,21 @@ namespace ArdupilotMega
return param;
}
public _param getParam()
void modifyParamForDisplay(bool fromapm, string paramname, ref float value)
{
throw new Exception("getParam Not implemented");
/*
_param temp = new _param();
temp.name = "none";
temp.value = 0;
return temp;
*/
if (paramname.ToUpper().EndsWith("_IMAX") || paramname.ToUpper().EndsWith("ALT_HOLD_RTL") || paramname.ToUpper().EndsWith("TRIM_ARSPD_CM")
|| paramname.ToUpper().EndsWith("XTRK_ANGLE_CD") || paramname.ToUpper().EndsWith("LIM_PITCH_MAX") || paramname.ToUpper().EndsWith("LIM_PITCH_MIN")
|| paramname.ToUpper().EndsWith("LIM_ROLL_CD") || paramname.ToUpper().EndsWith("PITCH_MAX") || paramname.ToUpper().EndsWith("WP_SPEED_MAX"))
{
if (fromapm)
{
value /= 100.0f;
}
else
{
value *= 100.0f;
}
}
}
/// <summary>
@ -1422,7 +1496,7 @@ namespace ArdupilotMega
}
catch (Exception e) { Console.WriteLine("MAVLink readpacket read error: " + e.Message); break; }
if (temp[0] != 'U' || lastbad[0] == 'I' && lastbad[1] == 'M') // out of sync
if (temp[0] != 254 && temp[0] != 'U' || lastbad[0] == 'I' && lastbad[1] == 'M') // out of sync
{
if (temp[0] >= 0x20 && temp[0] <= 127 || temp[0] == '\n')
{
@ -1437,7 +1511,7 @@ namespace ArdupilotMega
// reset count on valid packet
readcount = 0;
if (temp[0] == 'U')
if (temp[0] == 'U' || temp[0] == 254)
{
length = temp[1] + 6 + 2 - 2; // data + header + checksum - U - length
if (count >= 5 || logreadmode)
@ -1468,7 +1542,7 @@ namespace ArdupilotMega
break;
}
System.Threading.Thread.Sleep(1);
//System.Windows.Forms.Application.DoEvents();
System.Windows.Forms.Application.DoEvents();
to++;
//Console.WriteLine("data " + 0 + " " + length + " aval " + BaseStream.BytesToRead);
@ -1493,7 +1567,7 @@ namespace ArdupilotMega
if (bpstime.Second != DateTime.Now.Second && !logreadmode)
{
Console.WriteLine("bps {0} loss {1} left {2}", bps1, packetslost, BaseStream.BytesToRead);
Console.WriteLine("bps {0} loss {1} left {2}", bps1, synclost, BaseStream.BytesToRead);
bps2 = bps1; // prev sec
bps1 = 0; // current sec
bpstime = DateTime.Now;
@ -1505,11 +1579,16 @@ namespace ArdupilotMega
if (temp.Length >= 5 && temp[3] == 255 && logreadmode) // gcs packet
{
return new byte[0];
return temp;// new byte[0];
}
ushort crc = crc_calculate(temp, temp.Length - 2);
if (temp.Length > 5 && temp[0] == 254)
{
crc = crc_accumulate(MAVLINK_MESSAGE_CRCS[temp[5]], crc);
}
if (temp.Length < 5 || temp[temp.Length - 1] != (crc >> 8) || temp[temp.Length - 2] != (crc & 0xff))
{
int packetno = 0;
@ -1523,13 +1602,35 @@ namespace ArdupilotMega
try
{
if (temp[0] == 'U' && temp.Length >= temp[1])
if ((temp[0] == 'U' || temp[0] == 254) && temp.Length >= temp[1])
{
if (temp[2] != ((recvpacketcount + 1) % 0x100))
{
Console.WriteLine("lost {0}", temp[2]);
packetslost++; // actualy sync loss's
synclost++; // actualy sync loss's
if (temp[2] < ((recvpacketcount + 1) % 0x100))
{
packetslost += 0x100 - recvpacketcount + temp[2];
}
else
{
packetslost += temp[2] - recvpacketcount;
}
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++;
recvpacketcount = temp[2];
//MAVLINK_MSG_ID_GPS_STATUS
@ -1679,6 +1780,8 @@ namespace ArdupilotMega
lastlogread = date1;
MainV2.cs.datetime = lastlogread;
int length = 5;
int a = 0;
while (a < length)
@ -1758,6 +1861,34 @@ namespace ArdupilotMega
}
public static void ByteArrayToStructure(byte[] bytearray, ref object obj, int startoffset)
{
if (bytearray[0] == 'U')
{
ByteArrayToStructureEndian(bytearray, ref obj, startoffset);
}
else
{
int len = Marshal.SizeOf(obj);
IntPtr i = Marshal.AllocHGlobal(len);
// create structure from ptr
obj = Marshal.PtrToStructure(i, obj.GetType());
try
{
// copy byte array to ptr
Marshal.Copy(bytearray, startoffset, i, len);
}
catch (Exception ex) { Console.WriteLine("ByteArrayToStructure FAIL: error " + ex.ToString()); }
obj = Marshal.PtrToStructure(i, obj.GetType());
Marshal.FreeHGlobal(i);
}
}
public static void ByteArrayToStructureEndian(byte[] bytearray, ref object obj, int startoffset)
{
int len = Marshal.SizeOf(obj);
@ -1786,51 +1917,12 @@ namespace ArdupilotMega
TypeCode typeCode = Type.GetTypeCode(fieldValue.GetType());
if (typeCode != TypeCode.Object)
{/*
switch (Marshal.SizeOf(fieldValue))
{
case 1:
Marshal.WriteByte(i, reversestartoffset - 6, bytearray[reversestartoffset]);
break;
case 2:
byte[] temp = new byte[2];
temp[0] = bytearray[reversestartoffset + 1];
temp[1] = bytearray[reversestartoffset + 0];
Marshal.WriteInt16(i, reversestartoffset - 6, BitConverter.ToInt16(temp, 0));
break;
case 4:
byte[] temp2 = new byte[4];
temp2[0] = bytearray[reversestartoffset + 3];
temp2[1] = bytearray[reversestartoffset + 2];
temp2[2] = bytearray[reversestartoffset + 1];
temp2[3] = bytearray[reversestartoffset + 0];
Marshal.WriteInt32(i, reversestartoffset - 6, BitConverter.ToInt32(temp2, 0));
break;
case 8:
byte[] temp3 = new byte[8];
temp3[0] = bytearray[reversestartoffset + 7];
temp3[1] = bytearray[reversestartoffset + 6];
temp3[2] = bytearray[reversestartoffset + 5];
temp3[3] = bytearray[reversestartoffset + 4];
temp3[4] = bytearray[reversestartoffset + 3];
temp3[5] = bytearray[reversestartoffset + 2];
temp3[6] = bytearray[reversestartoffset + 1];
temp3[7] = bytearray[reversestartoffset + 0];
Marshal.WriteInt64(i, reversestartoffset - 6, BitConverter.ToInt64(temp3, 0));
break;
default:
Console.WriteLine("bytearraytostruct Bad value");
break;
} */
{
Array.Reverse(temparray, reversestartoffset, Marshal.SizeOf(fieldValue));
reversestartoffset += Marshal.SizeOf(fieldValue);
}
else
{
/*
for (int c = 0; c < ((byte[])fieldValue).Length;c++)
Marshal.WriteByte(i, c, bytearray[reversestartoffset + c]);
*/
reversestartoffset += ((byte[])fieldValue).Length;
}

File diff suppressed because it is too large Load Diff

View File

@ -7,159 +7,7 @@ namespace ArdupilotMega
{
partial class MAVLink
{
public enum MAV_CLASS
{
MAV_CLASS_GENERIC = 0, ///< Generic autopilot, full support for everything
MAV_CLASS_PIXHAWK = 1, ///< PIXHAWK autopilot, http://pixhawk.ethz.ch
MAV_CLASS_SLUGS = 2, ///< SLUGS autopilot, http://slugsuav.soe.ucsc.edu
MAV_CLASS_ARDUPILOTMEGA = 3, ///< ArduPilotMega / ArduCopter, http://diydrones.com
MAV_CLASS_OPENPILOT = 4, ///< OpenPilot, http://openpilot.org
MAV_CLASS_GENERIC_MISSION_WAYPOINTS_ONLY = 5, ///< Generic autopilot only supporting simple waypoints
MAV_CLASS_GENERIC_MISSION_NAVIGATION_ONLY = 6, ///< Generic autopilot supporting waypoints and other simple navigation commands
MAV_CLASS_GENERIC_MISSION_FULL = 7, ///< Generic autopilot supporting the full mission command set
MAV_CLASS_NONE = 8, ///< No valid autopilot
MAV_CLASS_NB ///< Number of autopilot classes
};
public enum MAV_ACTION
{
MAV_ACTION_HOLD = 0,
MAV_ACTION_MOTORS_START = 1,
MAV_ACTION_LAUNCH = 2,
MAV_ACTION_RETURN = 3,
MAV_ACTION_EMCY_LAND = 4,
MAV_ACTION_EMCY_KILL = 5,
MAV_ACTION_CONFIRM_KILL = 6,
MAV_ACTION_CONTINUE = 7,
MAV_ACTION_MOTORS_STOP = 8,
MAV_ACTION_HALT = 9,
MAV_ACTION_SHUTDOWN = 10,
MAV_ACTION_REBOOT = 11,
MAV_ACTION_SET_MANUAL = 12,
MAV_ACTION_SET_AUTO = 13,
MAV_ACTION_STORAGE_READ = 14,
MAV_ACTION_STORAGE_WRITE = 15,
MAV_ACTION_CALIBRATE_RC = 16,
MAV_ACTION_CALIBRATE_GYRO = 17,
MAV_ACTION_CALIBRATE_MAG = 18,
MAV_ACTION_CALIBRATE_ACC = 19,
MAV_ACTION_CALIBRATE_PRESSURE = 20,
MAV_ACTION_REC_START = 21,
MAV_ACTION_REC_PAUSE = 22,
MAV_ACTION_REC_STOP = 23,
MAV_ACTION_TAKEOFF = 24,
MAV_ACTION_NAVIGATE = 25,
MAV_ACTION_LAND = 26,
MAV_ACTION_LOITER = 27,
MAV_ACTION_SET_ORIGIN = 28,
MAV_ACTION_RELAY_ON = 29,
MAV_ACTION_RELAY_OFF = 30,
MAV_ACTION_GET_IMAGE = 31,
MAV_ACTION_VIDEO_START = 32,
MAV_ACTION_VIDEO_STOP = 33,
MAV_ACTION_RESET_MAP = 34,
MAV_ACTION_RESET_PLAN = 35,
MAV_ACTION_DELAY_BEFORE_COMMAND = 36,
MAV_ACTION_ASCEND_AT_RATE = 37,
MAV_ACTION_CHANGE_MODE = 38,
MAV_ACTION_LOITER_MAX_TURNS = 39,
MAV_ACTION_LOITER_MAX_TIME = 40,
MAV_ACTION_START_HILSIM = 41,
MAV_ACTION_STOP_HILSIM = 42,
MAV_ACTION_NB ///< Number of MAV actions
};
public enum MAV_MODE
{
MAV_MODE_UNINIT = 0, ///< System is in undefined state
MAV_MODE_LOCKED = 1, ///< Motors are blocked, system is safe
MAV_MODE_MANUAL = 2, ///< System is allowed to be active, under manual (RC) control
MAV_MODE_GUIDED = 3, ///< System is allowed to be active, under autonomous control, manual setpoint
MAV_MODE_AUTO = 4, ///< System is allowed to be active, under autonomous control and navigation
MAV_MODE_TEST1 = 5, ///< Generic test mode, for custom use
MAV_MODE_TEST2 = 6, ///< Generic test mode, for custom use
MAV_MODE_TEST3 = 7, ///< Generic test mode, for custom use
MAV_MODE_READY = 8, ///< System is ready, motors are unblocked, but controllers are inactive
MAV_MODE_RC_TRAINING = 9 ///< System is blocked, only RC valued are read and reported back
};
public enum MAV_STATE
{
MAV_STATE_UNINIT = 0,
MAV_STATE_BOOT,
MAV_STATE_CALIBRATING,
MAV_STATE_STANDBY,
MAV_STATE_ACTIVE,
MAV_STATE_CRITICAL,
MAV_STATE_EMERGENCY,
MAV_STATE_HILSIM,
MAV_STATE_POWEROFF
};
public enum MAV_NAV
{
MAV_NAV_GROUNDED = 0,
MAV_NAV_LIFTOFF,
MAV_NAV_HOLD,
MAV_NAV_WAYPOINT,
MAV_NAV_VECTOR,
MAV_NAV_RETURNING,
MAV_NAV_LANDING,
MAV_NAV_LOST,
MAV_NAV_LOITER,
MAV_NAV_FREE_DRIFT
};
public enum MAV_TYPE
{
MAV_GENERIC = 0,
MAV_FIXED_WING = 1,
MAV_QUADROTOR = 2,
MAV_COAXIAL = 3,
MAV_HELICOPTER = 4,
MAV_GROUND = 5,
OCU = 6,
MAV_AIRSHIP = 7,
MAV_FREE_BALLOON = 8,
MAV_ROCKET = 9,
UGV_GROUND_ROVER = 10,
UGV_SURFACE_SHIP = 11
};
public enum MAV_AUTOPILOT_TYPE
{
MAV_AUTOPILOT_GENERIC = 0,
MAV_AUTOPILOT_PIXHAWK = 1,
MAV_AUTOPILOT_SLUGS = 2,
MAV_AUTOPILOT_ARDUPILOTMEGA = 3,
MAV_AUTOPILOT_NONE = 4
};
public enum MAV_COMPONENT
{
MAV_COMP_ID_GPS,
MAV_COMP_ID_WAYPOINTPLANNER,
MAV_COMP_ID_BLOBTRACKER,
MAV_COMP_ID_PATHPLANNER,
MAV_COMP_ID_AIRSLAM,
MAV_COMP_ID_MAPPER,
MAV_COMP_ID_CAMERA,
MAV_COMP_ID_IMU = 200,
MAV_COMP_ID_IMU_2 = 201,
MAV_COMP_ID_IMU_3 = 202,
MAV_COMP_ID_UDP_BRIDGE = 240,
MAV_COMP_ID_UART_BRIDGE = 241,
MAV_COMP_ID_SYSTEM_CONTROL = 250
};
public enum MAV_FRAME
{
MAV_FRAME_GLOBAL = 0,
MAV_FRAME_LOCAL = 1,
MAV_FRAME_MISSION = 2,
MAV_FRAME_GLOBAL_RELATIVE_ALT = 3,
MAV_FRAME_LOCAL_ENU = 4
};
}
}

View File

@ -76,7 +76,13 @@ namespace ArdupilotMega
//System.Threading.Thread.CurrentThread.CurrentUICulture = new System.Globalization.CultureInfo("en-US");
//System.Threading.Thread.CurrentThread.CurrentCulture = new System.Globalization.CultureInfo("en-US");
srtm.datadirectory = @"C:\srtm";
srtm.datadirectory = Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + "srtm";
georefimage temp = new georefimage();
//temp.dowork(141);
//return;
var t = Type.GetType("Mono.Runtime");
MAC = (t != null);
@ -155,6 +161,15 @@ namespace ArdupilotMega
}
catch (Exception e) { MessageBox.Show("A Major error has occured : " + e.ToString()); this.Close(); }
GCSViews.FlightData.myhud.Refresh();
GCSViews.FlightData.myhud.Refresh();
GCSViews.FlightData.myhud.Refresh();
if (GCSViews.FlightData.myhud.huddrawtime > 1000)
{
MessageBox.Show("The HUD draw time is above 1 seconds. Please update your graphics card driver.");
}
changeunits();
try
@ -941,7 +956,7 @@ namespace ArdupilotMega
if (heatbeatsend.Second != DateTime.Now.Second)
{
Console.WriteLine("remote lost {0}", cs.packetdrop);
Console.WriteLine("remote lost {0}", cs.packetdropremote);
MAVLink.__mavlink_heartbeat_t htb = new MAVLink.__mavlink_heartbeat_t();
@ -954,10 +969,13 @@ namespace ArdupilotMega
}
// data loss warning
if (speechenable && talk != null && (DateTime.Now - comPort.lastvalidpacket).TotalSeconds > 10)
if ((DateTime.Now - comPort.lastvalidpacket).TotalSeconds > 10)
{
if (MainV2.talk.State == SynthesizerState.Ready)
MainV2.talk.SpeakAsync("WARNING No Data for " + (int)(DateTime.Now - comPort.lastvalidpacket).TotalSeconds + " Seconds");
if (speechenable && talk != null) {
if (MainV2.talk.State == SynthesizerState.Ready)
MainV2.talk.SpeakAsync("WARNING No Data for " + (int)(DateTime.Now - comPort.lastvalidpacket).TotalSeconds + " Seconds");
}
MainV2.cs.linkqualitygcs = 0;
}
//Console.WriteLine(comPort.BaseStream.BytesToRead);

View File

@ -431,13 +431,14 @@ namespace ArdupilotMega
// bar moves to 100 % in this step
progressBar1.Value = (int)((float)mine.logplaybackfile.BaseStream.Position / (float)mine.logplaybackfile.BaseStream.Length * 100.0f / 1.0f);
Application.DoEvents();
progressBar1.Refresh();
//Application.DoEvents();
byte[] packet = mine.readPacket();
string text = "";
mine.DebugPacket(packet, ref text);
sw.Write(text);
sw.Write(mine.lastlogread +" "+text);
}
sw.Close();

View File

@ -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.0.68")]
[assembly: AssemblyFileVersion("1.0.69")]
[assembly: NeutralResourcesLanguageAttribute("")]

View File

@ -1,4 +1,4 @@
== MAVLink Parameters ==
== MAVLink Parameters == (this is a copy fo the wiki page FYI)
This is a list of all the user-modifiable MAVLink parameters and what they do. You can modify them via the MAVLink parameters window in any compatible GCS, such as the Mission Planner, HK GCS or !QGroundControl.
@ -213,9 +213,9 @@ It includes both fixed wing (APM) and rotary wing (!ArduCopter) parameters. Some
||SYSID_SW_MREV|| || ||0|| || ||Description coming soon||
||SYSID_SW_TYPE|| || ||0|| || ||Description coming soon||
||THR_SLEWRATE||0||100||0||1||1||THROTTLE_SLEW_RATE - 0 = Disabled, otherwise it limits throttle movement rate. Units are % per second. This is a test feature and may go away.||
||FLTMODE1||0||20||1||1|| ||FLIGHT_MODE_1 - Mode switch setting 1 - APM: 0 = Manual, 2 = Stabilize, 5 - Fly-By-Wire-A, 6 = Fly-By-Wire-B, 7 = Fly-By-Wire-C, 10 = Auto - Mission, 11 = RTL, 12 = Loiter, 13 = Take-off, 14 = Land, 15= Guided; ACM2: 0 = Stabilize, 2 = Acro, 3 = Simple, 4 = Auto, 5 = Guided, 6 = Loiter, 7 = RTL||
||FLTMODE2||0||20||1||1|| ||FLIGHT_MODE_2 - Mode switch setting 2 - APM: 0 = Manual, 2 = Stabilize, 5 - Fly-By-Wire-A, 6 = Fly-By-Wire-B, 7 = Fly-By-Wire-C, 10 = Auto - Mission, 11 = RTL, 12 = Loiter, 13 = Take-off, 14 = Land, 15= Guided; ACM2: 0 = Stabilize, 2 = Acro, 3 = Simple, 4 = Auto, 5 = Guided, 6 = Loiter, 7 = RTL||
||FLTMODE3||0||20||1||1|| ||FLIGHT_MODE_3 - Mode switch setting 3 - APM: 0 = Manual, 2 = Stabilize, 5 - Fly-By-Wire-A, 6 = Fly-By-Wire-B, 7 = Fly-By-Wire-C, 10 = Auto - Mission, 11 = RTL, 12 = Loiter, 13 = Take-off, 14 = Land, 15= Guided; ACM2: 0 = Stabilize, 2 = Acro, 3 = Simple, 4 = Auto, 5 = Guided, 6 = Loiter, 7 = RTL||
||FLTMODE4||0||20||1||1|| ||FLIGHT_MODE_4 - Mode switch setting 4 - APM: 0 = Manual, 2 = Stabilize, 5 - Fly-By-Wire-A, 6 = Fly-By-Wire-B, 7 = Fly-By-Wire-C, 10 = Auto - Mission, 11 = RTL, 12 = Loiter, 13 = Take-off, 14 = Land, 15= Guided; ACM2: 0 = Stabilize, 2 = Acro, 3 = Simple, 4 = Auto, 5 = Guided, 6 = Loiter, 7 = RTL||
||FLTMODE5||0||20||1||1|| ||FLIGHT_MODE_5 - Mode switch setting 5 - APM: 0 = Manual, 2 = Stabilize, 5 - Fly-By-Wire-A, 6 = Fly-By-Wire-B, 7 = Fly-By-Wire-C, 10 = Auto - Mission, 11 = RTL, 12 = Loiter, 13 = Take-off, 14 = Land, 15= Guided; ACM2: 0 = Stabilize, 2 = Acro, 3 = Simple, 4 = Auto, 5 = Guided, 6 = Loiter, 7 = RTL||
||FLTMODE6||0||20||1||1|| ||FLIGHT_MODE_6 - Mode switch setting 6 - APM: 0 = Manual, 2 = Stabilize, 5 - Fly-By-Wire-A, 6 = Fly-By-Wire-B, 7 = Fly-By-Wire-C, 10 = Auto - Mission, 11 = RTL, 12 = Loiter, 13 = Take-off, 14 = Land, 15= Guided; ACM2: 0 = Stabilize, 2 = Acro, 3 = Simple, 4 = Auto, 5 = Guided, 6 = Loiter, 7 = RTL||
||FLTMODE1||0||20||1||1|| ||FLIGHT_MODE_1 - Mode switch setting 1 - APM: 0 = Manual, 2 = Stabilize, 5 - Fly-By-Wire-A, 6 = Fly-By-Wire-B, 7 = Fly-By-Wire-C, 10 = Auto - Mission, 11 = RTL, 12 = Loiter, 13 = Take-off, 14 = Land, 15= Guided; ACM2: 0 = Stabilize, 1 = Acro, 2 = Alt Hold, 3 = Auto, 4 = Guided, 5 = Loiter, 6 = RTL||
||FLTMODE2||0||20||1||1|| ||FLIGHT_MODE_2 - Mode switch setting 2 - APM: 0 = Manual, 2 = Stabilize, 5 - Fly-By-Wire-A, 6 = Fly-By-Wire-B, 7 = Fly-By-Wire-C, 10 = Auto - Mission, 11 = RTL, 12 = Loiter, 13 = Take-off, 14 = Land, 15= Guided; ACM2: 0 = Stabilize, 1 = Acro, 2 = Alt Hold, 3 = Auto, 4 = Guided, 5 = Loiter, 6 = RTL||
||FLTMODE3||0||20||1||1|| ||FLIGHT_MODE_3 - Mode switch setting 3 - APM: 0 = Manual, 2 = Stabilize, 5 - Fly-By-Wire-A, 6 = Fly-By-Wire-B, 7 = Fly-By-Wire-C, 10 = Auto - Mission, 11 = RTL, 12 = Loiter, 13 = Take-off, 14 = Land, 15= Guided; ACM2: 0 = Stabilize, 1 = Acro, 2 = Alt Hold, 3 = Auto, 4 = Guided, 5 = Loiter, 6 = RTL||
||FLTMODE4||0||20||1||1|| ||FLIGHT_MODE_4 - Mode switch setting 4 - APM: 0 = Manual, 2 = Stabilize, 5 - Fly-By-Wire-A, 6 = Fly-By-Wire-B, 7 = Fly-By-Wire-C, 10 = Auto - Mission, 11 = RTL, 12 = Loiter, 13 = Take-off, 14 = Land, 15= Guided; ACM2: 0 = Stabilize, 1 = Acro, 2 = Alt Hold, 3 = Auto, 4 = Guided, 5 = Loiter, 6 = RTL||
||FLTMODE5||0||20||1||1|| ||FLIGHT_MODE_5 - Mode switch setting 5 - APM: 0 = Manual, 2 = Stabilize, 5 - Fly-By-Wire-A, 6 = Fly-By-Wire-B, 7 = Fly-By-Wire-C, 10 = Auto - Mission, 11 = RTL, 12 = Loiter, 13 = Take-off, 14 = Land, 15= Guided; ACM2: 0 = Stabilize, 1 = Acro, 2 = Alt Hold, 3 = Auto, 4 = Guided, 5 = Loiter, 6 = RTL||
||FLTMODE6||0||20||1||1|| ||FLIGHT_MODE_6 - Mode switch setting 6 - APM: 0 = Manual, 2 = Stabilize, 5 - Fly-By-Wire-A, 6 = Fly-By-Wire-B, 7 = Fly-By-Wire-C, 10 = Auto - Mission, 11 = RTL, 12 = Loiter, 13 = Take-off, 14 = Land, 15= Guided; ACM2: 0 = Stabilize, 1 = Acro, 2 = Alt Hold, 3 = Auto, 4 = Guided, 5 = Loiter, 6 = RTL||

View File

@ -32,22 +32,11 @@
System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(Setup));
this.tabControl1 = new System.Windows.Forms.TabControl();
this.tabReset = new System.Windows.Forms.TabPage();
this.BUT_reset = new ArdupilotMega.MyButton();
this.tabRadioIn = new System.Windows.Forms.TabPage();
this.CHK_revch3 = new System.Windows.Forms.CheckBox();
this.CHK_revch4 = new System.Windows.Forms.CheckBox();
this.CHK_revch2 = new System.Windows.Forms.CheckBox();
this.CHK_revch1 = new System.Windows.Forms.CheckBox();
this.BUT_Calibrateradio = new ArdupilotMega.MyButton();
this.BAR8 = new ArdupilotMega.HorizontalProgressBar2();
this.currentStateBindingSource = new System.Windows.Forms.BindingSource(this.components);
this.BAR7 = new ArdupilotMega.HorizontalProgressBar2();
this.BAR6 = new ArdupilotMega.HorizontalProgressBar2();
this.BAR5 = new ArdupilotMega.HorizontalProgressBar2();
this.BARpitch = new ArdupilotMega.VerticalProgressBar2();
this.BARthrottle = new ArdupilotMega.VerticalProgressBar2();
this.BARyaw = new ArdupilotMega.HorizontalProgressBar2();
this.BARroll = new ArdupilotMega.HorizontalProgressBar2();
this.tabModes = new System.Windows.Forms.TabPage();
this.label14 = new System.Windows.Forms.Label();
this.LBL_flightmodepwm = new System.Windows.Forms.Label();
@ -71,7 +60,6 @@
this.CMB_fmode2 = new System.Windows.Forms.ComboBox();
this.label1 = new System.Windows.Forms.Label();
this.CMB_fmode1 = new System.Windows.Forms.ComboBox();
this.BUT_SaveModes = new ArdupilotMega.MyButton();
this.tabHardware = new System.Windows.Forms.TabPage();
this.linkLabelmagdec = new System.Windows.Forms.LinkLabel();
this.label106 = new System.Windows.Forms.Label();
@ -90,7 +78,6 @@
this.pictureBox1 = new System.Windows.Forms.PictureBox();
this.tabArducopter = new System.Windows.Forms.TabPage();
this.label28 = new System.Windows.Forms.Label();
this.BUT_levelac2 = new ArdupilotMega.MyButton();
this.label16 = new System.Windows.Forms.Label();
this.label15 = new System.Windows.Forms.Label();
this.pictureBoxQuadX = new System.Windows.Forms.PictureBox();
@ -119,6 +106,20 @@
this.HS2_REV = new System.Windows.Forms.CheckBox();
this.HS1_REV = new System.Windows.Forms.CheckBox();
this.label17 = new System.Windows.Forms.Label();
this.toolTip1 = new System.Windows.Forms.ToolTip(this.components);
this.BUT_reset = new ArdupilotMega.MyButton();
this.BUT_Calibrateradio = new ArdupilotMega.MyButton();
this.BAR8 = new ArdupilotMega.HorizontalProgressBar2();
this.currentStateBindingSource = new System.Windows.Forms.BindingSource(this.components);
this.BAR7 = new ArdupilotMega.HorizontalProgressBar2();
this.BAR6 = new ArdupilotMega.HorizontalProgressBar2();
this.BAR5 = new ArdupilotMega.HorizontalProgressBar2();
this.BARpitch = new ArdupilotMega.VerticalProgressBar2();
this.BARthrottle = new ArdupilotMega.VerticalProgressBar2();
this.BARyaw = new ArdupilotMega.HorizontalProgressBar2();
this.BARroll = new ArdupilotMega.HorizontalProgressBar2();
this.BUT_SaveModes = new ArdupilotMega.MyButton();
this.BUT_levelac2 = new ArdupilotMega.MyButton();
this.BUT_saveheliconfig = new ArdupilotMega.MyButton();
this.BUT_0collective = new ArdupilotMega.MyButton();
this.HS4 = new ArdupilotMega.VerticalProgressBar2();
@ -128,11 +129,15 @@
this.HS2_TRIM = new ArdupilotMega.MyTrackBar();
this.HS1_TRIM = new ArdupilotMega.MyTrackBar();
this.Gservoloc = new AGaugeApp.AGauge();
this.toolTip1 = new System.Windows.Forms.ToolTip(this.components);
this.CB_simple1 = new System.Windows.Forms.CheckBox();
this.CB_simple2 = new System.Windows.Forms.CheckBox();
this.CB_simple3 = new System.Windows.Forms.CheckBox();
this.CB_simple4 = new System.Windows.Forms.CheckBox();
this.CB_simple5 = new System.Windows.Forms.CheckBox();
this.CB_simple6 = new System.Windows.Forms.CheckBox();
this.tabControl1.SuspendLayout();
this.tabReset.SuspendLayout();
this.tabRadioIn.SuspendLayout();
((System.ComponentModel.ISupportInitialize)(this.currentStateBindingSource)).BeginInit();
this.tabModes.SuspendLayout();
this.tabHardware.SuspendLayout();
((System.ComponentModel.ISupportInitialize)(this.pictureBox4)).BeginInit();
@ -143,6 +148,7 @@
((System.ComponentModel.ISupportInitialize)(this.pictureBoxQuadX)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.pictureBoxQuad)).BeginInit();
this.tabHeli.SuspendLayout();
((System.ComponentModel.ISupportInitialize)(this.currentStateBindingSource)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.HS4_TRIM)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.HS3_TRIM)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.HS2_TRIM)).BeginInit();
@ -169,14 +175,6 @@
this.tabReset.Name = "tabReset";
this.tabReset.UseVisualStyleBackColor = true;
//
// BUT_reset
//
resources.ApplyResources(this.BUT_reset, "BUT_reset");
this.BUT_reset.Name = "BUT_reset";
this.BUT_reset.Tag = "";
this.BUT_reset.UseVisualStyleBackColor = true;
this.BUT_reset.Click += new System.EventHandler(this.BUT_reset_Click);
//
// tabRadioIn
//
this.tabRadioIn.Controls.Add(this.CHK_revch3);
@ -224,139 +222,14 @@
this.CHK_revch1.UseVisualStyleBackColor = true;
this.CHK_revch1.CheckedChanged += new System.EventHandler(this.CHK_revch1_CheckedChanged);
//
// BUT_Calibrateradio
//
resources.ApplyResources(this.BUT_Calibrateradio, "BUT_Calibrateradio");
this.BUT_Calibrateradio.Name = "BUT_Calibrateradio";
this.BUT_Calibrateradio.UseVisualStyleBackColor = true;
this.BUT_Calibrateradio.Click += new System.EventHandler(this.BUT_Calibrateradio_Click);
//
// BAR8
//
this.BAR8.BackgroundColor = System.Drawing.Color.FromArgb(((int)(((byte)(20)))), ((int)(((byte)(20)))), ((int)(((byte)(255)))));
this.BAR8.BorderColor = System.Drawing.SystemColors.ActiveBorder;
this.BAR8.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.currentStateBindingSource, "ch8in", true));
this.BAR8.Label = "Radio 8";
resources.ApplyResources(this.BAR8, "BAR8");
this.BAR8.Maximum = 2200;
this.BAR8.maxline = 0;
this.BAR8.Minimum = 800;
this.BAR8.minline = 0;
this.BAR8.Name = "BAR8";
this.BAR8.Value = 1500;
this.BAR8.ValueColor = System.Drawing.Color.FromArgb(((int)(((byte)(255)))), ((int)(((byte)(0)))), ((int)(((byte)(255)))));
//
// currentStateBindingSource
//
this.currentStateBindingSource.DataSource = typeof(ArdupilotMega.CurrentState);
//
// BAR7
//
this.BAR7.BackgroundColor = System.Drawing.Color.FromArgb(((int)(((byte)(20)))), ((int)(((byte)(20)))), ((int)(((byte)(255)))));
this.BAR7.BorderColor = System.Drawing.SystemColors.ActiveBorder;
this.BAR7.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.currentStateBindingSource, "ch7in", true));
this.BAR7.Label = "Radio 7";
resources.ApplyResources(this.BAR7, "BAR7");
this.BAR7.Maximum = 2200;
this.BAR7.maxline = 0;
this.BAR7.Minimum = 800;
this.BAR7.minline = 0;
this.BAR7.Name = "BAR7";
this.BAR7.Value = 1500;
this.BAR7.ValueColor = System.Drawing.Color.FromArgb(((int)(((byte)(255)))), ((int)(((byte)(0)))), ((int)(((byte)(255)))));
//
// BAR6
//
this.BAR6.BackgroundColor = System.Drawing.Color.FromArgb(((int)(((byte)(20)))), ((int)(((byte)(20)))), ((int)(((byte)(255)))));
this.BAR6.BorderColor = System.Drawing.SystemColors.ActiveBorder;
this.BAR6.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.currentStateBindingSource, "ch6in", true));
this.BAR6.Label = "Radio 6";
resources.ApplyResources(this.BAR6, "BAR6");
this.BAR6.Maximum = 2200;
this.BAR6.maxline = 0;
this.BAR6.Minimum = 800;
this.BAR6.minline = 0;
this.BAR6.Name = "BAR6";
this.BAR6.Value = 1500;
this.BAR6.ValueColor = System.Drawing.Color.FromArgb(((int)(((byte)(255)))), ((int)(((byte)(0)))), ((int)(((byte)(255)))));
//
// BAR5
//
this.BAR5.BackgroundColor = System.Drawing.Color.FromArgb(((int)(((byte)(20)))), ((int)(((byte)(20)))), ((int)(((byte)(255)))));
this.BAR5.BorderColor = System.Drawing.SystemColors.ActiveBorder;
this.BAR5.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.currentStateBindingSource, "ch5in", true));
this.BAR5.Label = "Radio 5";
resources.ApplyResources(this.BAR5, "BAR5");
this.BAR5.Maximum = 2200;
this.BAR5.maxline = 0;
this.BAR5.Minimum = 800;
this.BAR5.minline = 0;
this.BAR5.Name = "BAR5";
this.BAR5.Value = 1500;
this.BAR5.ValueColor = System.Drawing.Color.FromArgb(((int)(((byte)(255)))), ((int)(((byte)(0)))), ((int)(((byte)(255)))));
//
// BARpitch
//
this.BARpitch.BackgroundColor = System.Drawing.Color.FromArgb(((int)(((byte)(20)))), ((int)(((byte)(20)))), ((int)(((byte)(255)))));
this.BARpitch.BorderColor = System.Drawing.SystemColors.ActiveBorder;
this.BARpitch.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.currentStateBindingSource, "ch2in", true));
this.BARpitch.Label = "Pitch";
resources.ApplyResources(this.BARpitch, "BARpitch");
this.BARpitch.Maximum = 2200;
this.BARpitch.maxline = 0;
this.BARpitch.Minimum = 800;
this.BARpitch.minline = 0;
this.BARpitch.Name = "BARpitch";
this.BARpitch.Value = 1500;
this.BARpitch.ValueColor = System.Drawing.Color.FromArgb(((int)(((byte)(255)))), ((int)(((byte)(0)))), ((int)(((byte)(255)))));
//
// BARthrottle
//
this.BARthrottle.BackgroundColor = System.Drawing.Color.FromArgb(((int)(((byte)(67)))), ((int)(((byte)(68)))), ((int)(((byte)(69)))));
this.BARthrottle.BorderColor = System.Drawing.SystemColors.ActiveBorder;
this.BARthrottle.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.currentStateBindingSource, "ch3in", true));
this.BARthrottle.Label = "Throttle";
resources.ApplyResources(this.BARthrottle, "BARthrottle");
this.BARthrottle.Maximum = 2200;
this.BARthrottle.maxline = 0;
this.BARthrottle.Minimum = 800;
this.BARthrottle.minline = 0;
this.BARthrottle.Name = "BARthrottle";
this.BARthrottle.Value = 1000;
this.BARthrottle.ValueColor = System.Drawing.Color.FromArgb(((int)(((byte)(148)))), ((int)(((byte)(193)))), ((int)(((byte)(31)))));
//
// BARyaw
//
this.BARyaw.BackgroundColor = System.Drawing.Color.FromArgb(((int)(((byte)(20)))), ((int)(((byte)(20)))), ((int)(((byte)(255)))));
this.BARyaw.BorderColor = System.Drawing.SystemColors.ActiveBorder;
this.BARyaw.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.currentStateBindingSource, "ch4in", true));
this.BARyaw.Label = "Yaw";
resources.ApplyResources(this.BARyaw, "BARyaw");
this.BARyaw.Maximum = 2200;
this.BARyaw.maxline = 0;
this.BARyaw.Minimum = 800;
this.BARyaw.minline = 0;
this.BARyaw.Name = "BARyaw";
this.BARyaw.Value = 1500;
this.BARyaw.ValueColor = System.Drawing.Color.FromArgb(((int)(((byte)(255)))), ((int)(((byte)(0)))), ((int)(((byte)(255)))));
//
// BARroll
//
this.BARroll.BackgroundColor = System.Drawing.Color.FromArgb(((int)(((byte)(20)))), ((int)(((byte)(20)))), ((int)(((byte)(255)))));
this.BARroll.BorderColor = System.Drawing.SystemColors.ActiveBorder;
this.BARroll.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.currentStateBindingSource, "ch1in", true));
this.BARroll.Label = "Roll";
resources.ApplyResources(this.BARroll, "BARroll");
this.BARroll.Maximum = 2200;
this.BARroll.maxline = 0;
this.BARroll.Minimum = 800;
this.BARroll.minline = 0;
this.BARroll.Name = "BARroll";
this.BARroll.Value = 1500;
this.BARroll.ValueColor = System.Drawing.Color.FromArgb(((int)(((byte)(255)))), ((int)(((byte)(0)))), ((int)(((byte)(255)))));
//
// tabModes
//
this.tabModes.Controls.Add(this.CB_simple6);
this.tabModes.Controls.Add(this.CB_simple5);
this.tabModes.Controls.Add(this.CB_simple4);
this.tabModes.Controls.Add(this.CB_simple3);
this.tabModes.Controls.Add(this.CB_simple2);
this.tabModes.Controls.Add(this.CB_simple1);
this.tabModes.Controls.Add(this.label14);
this.tabModes.Controls.Add(this.LBL_flightmodepwm);
this.tabModes.Controls.Add(this.label13);
@ -519,13 +392,6 @@
resources.ApplyResources(this.CMB_fmode1, "CMB_fmode1");
this.CMB_fmode1.Name = "CMB_fmode1";
//
// BUT_SaveModes
//
resources.ApplyResources(this.BUT_SaveModes, "BUT_SaveModes");
this.BUT_SaveModes.Name = "BUT_SaveModes";
this.BUT_SaveModes.UseVisualStyleBackColor = true;
this.BUT_SaveModes.Click += new System.EventHandler(this.BUT_SaveModes_Click);
//
// tabHardware
//
this.tabHardware.BackColor = System.Drawing.Color.DarkRed;
@ -661,11 +527,11 @@
// tabArducopter
//
this.tabArducopter.Controls.Add(this.label28);
this.tabArducopter.Controls.Add(this.BUT_levelac2);
this.tabArducopter.Controls.Add(this.label16);
this.tabArducopter.Controls.Add(this.label15);
this.tabArducopter.Controls.Add(this.pictureBoxQuadX);
this.tabArducopter.Controls.Add(this.pictureBoxQuad);
this.tabArducopter.Controls.Add(this.BUT_levelac2);
resources.ApplyResources(this.tabArducopter, "tabArducopter");
this.tabArducopter.Name = "tabArducopter";
this.tabArducopter.UseVisualStyleBackColor = true;
@ -675,13 +541,6 @@
resources.ApplyResources(this.label28, "label28");
this.label28.Name = "label28";
//
// BUT_levelac2
//
resources.ApplyResources(this.BUT_levelac2, "BUT_levelac2");
this.BUT_levelac2.Name = "BUT_levelac2";
this.BUT_levelac2.UseVisualStyleBackColor = true;
this.BUT_levelac2.Click += new System.EventHandler(this.BUT_levelac2_Click);
//
// label16
//
resources.ApplyResources(this.label16, "label16");
@ -879,6 +738,159 @@
resources.ApplyResources(this.label17, "label17");
this.label17.Name = "label17";
//
// BUT_reset
//
resources.ApplyResources(this.BUT_reset, "BUT_reset");
this.BUT_reset.Name = "BUT_reset";
this.BUT_reset.Tag = "";
this.BUT_reset.UseVisualStyleBackColor = true;
this.BUT_reset.Click += new System.EventHandler(this.BUT_reset_Click);
//
// BUT_Calibrateradio
//
resources.ApplyResources(this.BUT_Calibrateradio, "BUT_Calibrateradio");
this.BUT_Calibrateradio.Name = "BUT_Calibrateradio";
this.BUT_Calibrateradio.UseVisualStyleBackColor = true;
this.BUT_Calibrateradio.Click += new System.EventHandler(this.BUT_Calibrateradio_Click);
//
// BAR8
//
this.BAR8.BackgroundColor = System.Drawing.Color.FromArgb(((int)(((byte)(20)))), ((int)(((byte)(20)))), ((int)(((byte)(255)))));
this.BAR8.BorderColor = System.Drawing.SystemColors.ActiveBorder;
this.BAR8.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.currentStateBindingSource, "ch8in", true));
this.BAR8.Label = "Radio 8";
resources.ApplyResources(this.BAR8, "BAR8");
this.BAR8.Maximum = 2200;
this.BAR8.maxline = 0;
this.BAR8.Minimum = 800;
this.BAR8.minline = 0;
this.BAR8.Name = "BAR8";
this.BAR8.Value = 1500;
this.BAR8.ValueColor = System.Drawing.Color.FromArgb(((int)(((byte)(255)))), ((int)(((byte)(0)))), ((int)(((byte)(255)))));
//
// currentStateBindingSource
//
this.currentStateBindingSource.DataSource = typeof(ArdupilotMega.CurrentState);
//
// BAR7
//
this.BAR7.BackgroundColor = System.Drawing.Color.FromArgb(((int)(((byte)(20)))), ((int)(((byte)(20)))), ((int)(((byte)(255)))));
this.BAR7.BorderColor = System.Drawing.SystemColors.ActiveBorder;
this.BAR7.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.currentStateBindingSource, "ch7in", true));
this.BAR7.Label = "Radio 7";
resources.ApplyResources(this.BAR7, "BAR7");
this.BAR7.Maximum = 2200;
this.BAR7.maxline = 0;
this.BAR7.Minimum = 800;
this.BAR7.minline = 0;
this.BAR7.Name = "BAR7";
this.BAR7.Value = 1500;
this.BAR7.ValueColor = System.Drawing.Color.FromArgb(((int)(((byte)(255)))), ((int)(((byte)(0)))), ((int)(((byte)(255)))));
//
// BAR6
//
this.BAR6.BackgroundColor = System.Drawing.Color.FromArgb(((int)(((byte)(20)))), ((int)(((byte)(20)))), ((int)(((byte)(255)))));
this.BAR6.BorderColor = System.Drawing.SystemColors.ActiveBorder;
this.BAR6.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.currentStateBindingSource, "ch6in", true));
this.BAR6.Label = "Radio 6";
resources.ApplyResources(this.BAR6, "BAR6");
this.BAR6.Maximum = 2200;
this.BAR6.maxline = 0;
this.BAR6.Minimum = 800;
this.BAR6.minline = 0;
this.BAR6.Name = "BAR6";
this.BAR6.Value = 1500;
this.BAR6.ValueColor = System.Drawing.Color.FromArgb(((int)(((byte)(255)))), ((int)(((byte)(0)))), ((int)(((byte)(255)))));
//
// BAR5
//
this.BAR5.BackgroundColor = System.Drawing.Color.FromArgb(((int)(((byte)(20)))), ((int)(((byte)(20)))), ((int)(((byte)(255)))));
this.BAR5.BorderColor = System.Drawing.SystemColors.ActiveBorder;
this.BAR5.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.currentStateBindingSource, "ch5in", true));
this.BAR5.Label = "Radio 5";
resources.ApplyResources(this.BAR5, "BAR5");
this.BAR5.Maximum = 2200;
this.BAR5.maxline = 0;
this.BAR5.Minimum = 800;
this.BAR5.minline = 0;
this.BAR5.Name = "BAR5";
this.BAR5.Value = 1500;
this.BAR5.ValueColor = System.Drawing.Color.FromArgb(((int)(((byte)(255)))), ((int)(((byte)(0)))), ((int)(((byte)(255)))));
//
// BARpitch
//
this.BARpitch.BackgroundColor = System.Drawing.Color.FromArgb(((int)(((byte)(20)))), ((int)(((byte)(20)))), ((int)(((byte)(255)))));
this.BARpitch.BorderColor = System.Drawing.SystemColors.ActiveBorder;
this.BARpitch.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.currentStateBindingSource, "ch2in", true));
this.BARpitch.Label = "Pitch";
resources.ApplyResources(this.BARpitch, "BARpitch");
this.BARpitch.Maximum = 2200;
this.BARpitch.maxline = 0;
this.BARpitch.Minimum = 800;
this.BARpitch.minline = 0;
this.BARpitch.Name = "BARpitch";
this.BARpitch.Value = 1500;
this.BARpitch.ValueColor = System.Drawing.Color.FromArgb(((int)(((byte)(255)))), ((int)(((byte)(0)))), ((int)(((byte)(255)))));
//
// BARthrottle
//
this.BARthrottle.BackgroundColor = System.Drawing.Color.FromArgb(((int)(((byte)(67)))), ((int)(((byte)(68)))), ((int)(((byte)(69)))));
this.BARthrottle.BorderColor = System.Drawing.SystemColors.ActiveBorder;
this.BARthrottle.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.currentStateBindingSource, "ch3in", true));
this.BARthrottle.Label = "Throttle";
resources.ApplyResources(this.BARthrottle, "BARthrottle");
this.BARthrottle.Maximum = 2200;
this.BARthrottle.maxline = 0;
this.BARthrottle.Minimum = 800;
this.BARthrottle.minline = 0;
this.BARthrottle.Name = "BARthrottle";
this.BARthrottle.Value = 1000;
this.BARthrottle.ValueColor = System.Drawing.Color.FromArgb(((int)(((byte)(148)))), ((int)(((byte)(193)))), ((int)(((byte)(31)))));
//
// BARyaw
//
this.BARyaw.BackgroundColor = System.Drawing.Color.FromArgb(((int)(((byte)(20)))), ((int)(((byte)(20)))), ((int)(((byte)(255)))));
this.BARyaw.BorderColor = System.Drawing.SystemColors.ActiveBorder;
this.BARyaw.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.currentStateBindingSource, "ch4in", true));
this.BARyaw.Label = "Yaw";
resources.ApplyResources(this.BARyaw, "BARyaw");
this.BARyaw.Maximum = 2200;
this.BARyaw.maxline = 0;
this.BARyaw.Minimum = 800;
this.BARyaw.minline = 0;
this.BARyaw.Name = "BARyaw";
this.BARyaw.Value = 1500;
this.BARyaw.ValueColor = System.Drawing.Color.FromArgb(((int)(((byte)(255)))), ((int)(((byte)(0)))), ((int)(((byte)(255)))));
//
// BARroll
//
this.BARroll.BackgroundColor = System.Drawing.Color.FromArgb(((int)(((byte)(20)))), ((int)(((byte)(20)))), ((int)(((byte)(255)))));
this.BARroll.BorderColor = System.Drawing.SystemColors.ActiveBorder;
this.BARroll.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.currentStateBindingSource, "ch1in", true));
this.BARroll.Label = "Roll";
resources.ApplyResources(this.BARroll, "BARroll");
this.BARroll.Maximum = 2200;
this.BARroll.maxline = 0;
this.BARroll.Minimum = 800;
this.BARroll.minline = 0;
this.BARroll.Name = "BARroll";
this.BARroll.Value = 1500;
this.BARroll.ValueColor = System.Drawing.Color.FromArgb(((int)(((byte)(255)))), ((int)(((byte)(0)))), ((int)(((byte)(255)))));
//
// BUT_SaveModes
//
resources.ApplyResources(this.BUT_SaveModes, "BUT_SaveModes");
this.BUT_SaveModes.Name = "BUT_SaveModes";
this.BUT_SaveModes.UseVisualStyleBackColor = true;
this.BUT_SaveModes.Click += new System.EventHandler(this.BUT_SaveModes_Click);
//
// BUT_levelac2
//
resources.ApplyResources(this.BUT_levelac2, "BUT_levelac2");
this.BUT_levelac2.Name = "BUT_levelac2";
this.BUT_levelac2.UseVisualStyleBackColor = true;
this.BUT_levelac2.Click += new System.EventHandler(this.BUT_levelac2_Click);
//
// BUT_saveheliconfig
//
resources.ApplyResources(this.BUT_saveheliconfig, "BUT_saveheliconfig");
@ -925,8 +937,8 @@
//
// HS4_TRIM
//
this.HS4_TRIM.LargeChange = 1000;
resources.ApplyResources(this.HS4_TRIM, "HS4_TRIM");
this.HS4_TRIM.LargeChange = 1000;
this.HS4_TRIM.Maximum = 2000D;
this.HS4_TRIM.Minimum = 1000D;
this.HS4_TRIM.Name = "HS4_TRIM";
@ -937,8 +949,8 @@
//
// HS3_TRIM
//
this.HS3_TRIM.LargeChange = 1000;
resources.ApplyResources(this.HS3_TRIM, "HS3_TRIM");
this.HS3_TRIM.LargeChange = 1000;
this.HS3_TRIM.Maximum = 2000D;
this.HS3_TRIM.Minimum = 1000D;
this.HS3_TRIM.Name = "HS3_TRIM";
@ -949,8 +961,8 @@
//
// HS2_TRIM
//
this.HS2_TRIM.LargeChange = 1000;
resources.ApplyResources(this.HS2_TRIM, "HS2_TRIM");
this.HS2_TRIM.LargeChange = 1000;
this.HS2_TRIM.Maximum = 2000D;
this.HS2_TRIM.Minimum = 1000D;
this.HS2_TRIM.Name = "HS2_TRIM";
@ -961,8 +973,8 @@
//
// HS1_TRIM
//
this.HS1_TRIM.LargeChange = 1000;
resources.ApplyResources(this.HS1_TRIM, "HS1_TRIM");
this.HS1_TRIM.LargeChange = 1000;
this.HS1_TRIM.Maximum = 2000D;
this.HS1_TRIM.Minimum = 1000D;
this.HS1_TRIM.Name = "HS1_TRIM";
@ -1114,6 +1126,42 @@
this.Gservoloc.Value2 = 180F;
this.Gservoloc.Value3 = 0F;
//
// CB_simple1
//
resources.ApplyResources(this.CB_simple1, "CB_simple1");
this.CB_simple1.Name = "CB_simple1";
this.CB_simple1.UseVisualStyleBackColor = true;
//
// CB_simple2
//
resources.ApplyResources(this.CB_simple2, "CB_simple2");
this.CB_simple2.Name = "CB_simple2";
this.CB_simple2.UseVisualStyleBackColor = true;
//
// CB_simple3
//
resources.ApplyResources(this.CB_simple3, "CB_simple3");
this.CB_simple3.Name = "CB_simple3";
this.CB_simple3.UseVisualStyleBackColor = true;
//
// CB_simple4
//
resources.ApplyResources(this.CB_simple4, "CB_simple4");
this.CB_simple4.Name = "CB_simple4";
this.CB_simple4.UseVisualStyleBackColor = true;
//
// CB_simple5
//
resources.ApplyResources(this.CB_simple5, "CB_simple5");
this.CB_simple5.Name = "CB_simple5";
this.CB_simple5.UseVisualStyleBackColor = true;
//
// CB_simple6
//
resources.ApplyResources(this.CB_simple6, "CB_simple6");
this.CB_simple6.Name = "CB_simple6";
this.CB_simple6.UseVisualStyleBackColor = true;
//
// Setup
//
resources.ApplyResources(this, "$this");
@ -1126,7 +1174,6 @@
this.tabReset.ResumeLayout(false);
this.tabRadioIn.ResumeLayout(false);
this.tabRadioIn.PerformLayout();
((System.ComponentModel.ISupportInitialize)(this.currentStateBindingSource)).EndInit();
this.tabModes.ResumeLayout(false);
this.tabModes.PerformLayout();
this.tabHardware.ResumeLayout(false);
@ -1141,6 +1188,7 @@
((System.ComponentModel.ISupportInitialize)(this.pictureBoxQuad)).EndInit();
this.tabHeli.ResumeLayout(false);
this.tabHeli.PerformLayout();
((System.ComponentModel.ISupportInitialize)(this.currentStateBindingSource)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.HS4_TRIM)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.HS3_TRIM)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.HS2_TRIM)).EndInit();
@ -1250,6 +1298,12 @@
private System.Windows.Forms.CheckBox CHK_revch4;
private System.Windows.Forms.CheckBox CHK_revch2;
private System.Windows.Forms.CheckBox CHK_revch1;
private System.Windows.Forms.CheckBox CB_simple6;
private System.Windows.Forms.CheckBox CB_simple5;
private System.Windows.Forms.CheckBox CB_simple4;
private System.Windows.Forms.CheckBox CB_simple3;
private System.Windows.Forms.CheckBox CB_simple2;
private System.Windows.Forms.CheckBox CB_simple1;
}
}

View File

@ -252,6 +252,13 @@ namespace ArdupilotMega.Setup
{
if (MainV2.cs.firmware == MainV2.Firmwares.ArduPlane) // APM
{
CB_simple1.Visible = false;
CB_simple2.Visible = false;
CB_simple3.Visible = false;
CB_simple4.Visible = false;
CB_simple5.Visible = false;
CB_simple6.Visible = false;
CMB_fmode1.Items.Clear();
CMB_fmode2.Items.Clear();
CMB_fmode3.Items.Clear();
@ -410,6 +417,10 @@ namespace ArdupilotMega.Setup
MainV2.comPort.setParam("FLTMODE4", (float)(int)Enum.Parse(typeof(Common.ac2modes), CMB_fmode4.Text));
MainV2.comPort.setParam("FLTMODE5", (float)(int)Enum.Parse(typeof(Common.ac2modes), CMB_fmode5.Text));
MainV2.comPort.setParam("FLTMODE6", (float)(int)Enum.Parse(typeof(Common.ac2modes), CMB_fmode6.Text));
float value = (float)(CB_simple1.Checked ? 1 : 0) + (CB_simple2.Checked ? 1 << 1 : 0) + (CB_simple3.Checked ? 1 <<2 : 0)
+ (CB_simple4.Checked ? 1 << 3 : 0) + (CB_simple5.Checked ? 1 << 4 : 0) + (CB_simple6.Checked ? 1 << 5 : 0);
MainV2.comPort.setParam("SIMPLE", value);
}
}
catch { MessageBox.Show("Failed to set Flight modes"); }

File diff suppressed because it is too large Load Diff

View File

@ -22,9 +22,8 @@
<F1>WP Dist</F1>
<F2>WP Verify</F2>
<F3>Target Bear</F3>
<F4>Nav Bear</F4>
<F5>Long Err</F5>
<F6>Lat Err</F6>
<F4>Long Err</F4>
<F5>Lat Err</F5>
</NTUN>
<CTUN>
<F1>Yaw Sensor</F1>
@ -56,6 +55,13 @@
<F5>Accel Y</F5>
<F6>Accel Z</F6>
</RAW>
<CURR>
<F1>Throttle in</F1>
<F2>Throttle intergrator</F2>
<F3>Voltage</F3>
<F4>Current</F4>
<F5>Current total</F5>
</CURR>
</AC2>
<!-- -->
<APM>

View File

@ -22,9 +22,8 @@
<F1>WP Dist</F1>
<F2>WP Verify</F2>
<F3>Target Bear</F3>
<F4>Nav Bear</F4>
<F5>Long Err</F5>
<F6>Lat Err</F6>
<F4>Long Err</F4>
<F5>Lat Err</F5>
</NTUN>
<CTUN>
<F1>Yaw Sensor</F1>
@ -56,6 +55,13 @@
<F5>Accel Y</F5>
<F6>Accel Z</F6>
</RAW>
<CURR>
<F1>Throttle in</F1>
<F2>Throttle intergrator</F2>
<F3>Voltage</F3>
<F4>Current</F4>
<F5>Current total</F5>
</CURR>
</AC2>
<!-- -->
<APM>

View File

@ -0,0 +1,127 @@
using System;
using System.Collections.Generic;
using System.Linq;
using System.Text;
using System.Drawing;
using System.Drawing.Imaging;
using System.IO;
namespace ArdupilotMega
{
class georefimage
{
public string logFile = "";
public string dirWithImages = "";
DateTime getPhotoTime(string fn)
{
DateTime dtaken = DateTime.MinValue;
try
{
Image myImage = Image.FromFile(fn);
PropertyItem propItem = myImage.GetPropertyItem(36867); // 36867 // 306
//Convert date taken metadata to a DateTime object
string sdate = Encoding.UTF8.GetString(propItem.Value).Trim();
string secondhalf = sdate.Substring(sdate.IndexOf(" "), (sdate.Length - sdate.IndexOf(" ")));
string firsthalf = sdate.Substring(0, 10);
firsthalf = firsthalf.Replace(":", "-");
sdate = firsthalf + secondhalf;
dtaken = DateTime.Parse(sdate);
myImage.Dispose();
}
catch { }
return dtaken;
}
List<string[]> readLog(string fn)
{
List<string[]> list = new List<string[]>();
StreamReader sr = new StreamReader(fn);
string lasttime = "0";
while (!sr.EndOfStream)
{
string line = sr.ReadLine();
if (line.ToLower().StartsWith("gps"))
{
string[] vals = line.Split(new char[] {',',':'});
if (lasttime == vals[1])
continue;
lasttime = vals[1];
list.Add(vals);
}
}
sr.Close();
sr.Dispose();
return list;
}
public void dowork(float offsetseconds)
{
DateTime startTime = DateTime.MinValue;
logFile = @"C:\Users\hog\Pictures\sams mums 22-6-2011\23-06-11 10-03 4.log";
List<string[]> list = readLog(logFile);
dirWithImages = @"C:\Users\hog\Pictures\sams mums 22-6-2011";
string[] files = Directory.GetFiles(dirWithImages);
StreamWriter sw2 = new StreamWriter(dirWithImages + Path.DirectorySeparatorChar + "location.txt");
StreamWriter sw = new StreamWriter(dirWithImages + Path.DirectorySeparatorChar + "location.tel");
sw.WriteLine("version=1");
sw.WriteLine("#longitude and latitude - in degrees");
sw.WriteLine("#name utc longitude latitude height");
foreach (string file in files)
{
if (file.ToLower().EndsWith(".jpg"))
{
DateTime dt = getPhotoTime(file);
if (startTime == DateTime.MinValue)
startTime = new DateTime(dt.Year,dt.Month,dt.Day,0,0,0,0,DateTimeKind.Utc).ToLocalTime();
foreach (string[] arr in list)
{
DateTime crap = startTime.AddMilliseconds(int.Parse(arr[1])).AddSeconds(offsetseconds);
//Console.Write(dt + " " + crap + "\r");
if (dt.Equals(crap))
{
sw2.WriteLine(Path.GetFileNameWithoutExtension(file) + " " + arr[5] + " " + arr[4] + " " + arr[6]);
sw.WriteLine(Path.GetFileNameWithoutExtension(file) + "\t" + crap.ToString("yyyy:MM:dd HH:mm:ss") +"\t"+ arr[5] + "\t" + arr[4] + "\t" + arr[6]);
sw.Flush();
sw2.Flush();
Console.WriteLine(Path.GetFileNameWithoutExtension(file) + " " + arr[5] + " " + arr[4] + " " + arr[6] + " ");
break;
}
//Console.WriteLine(crap);
}
}
}
sw2.Close();
sw.Close();
}
}
}

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,132 @@
$dir = "C:/Users/hog/Documents/Arduino/libraries/GCS_MAVLink/message_definitions/";
#$dir = "C:/Users/hog/Desktop/DIYDrones&avr/pixhawk-mavlink-c91adfb/include/common/";
opendir(DIR,$dir) || die print $!;
@files = readdir(DIR);
closedir(DIR);
open(OUT,">MAVLinkTypes.cs");
print OUT <<EOF;
using System;
using System.Collections.Generic;
using System.Text;
using System.Runtime.InteropServices;
namespace ArdupilotMega
{
partial class MAVLink
{
EOF
foreach $file (@files) {
if (!($file eq "common.xml" || $file eq "ardupilotmega.xml"))
{
next;
}
print "$file\n";
open(F,$dir.$file);
$start = 0;
while ($line = <F>) {
if ($line =~ /enum name="(MAV_.*)"/) {
$start = 1;
print OUT "\t\tpublic enum $1\n\t\t{ \n";
}
if ($line =~ /<message id="([0-9]+)" name="([^"]+)">/) {
$name = lc($2);
print OUT "\t\tpublic const byte MAVLINK_MSG_ID_".uc($name) . " = " . $1 . ";\n";
print OUT "\t\t[StructLayout(LayoutKind.Sequential,Pack=1)]\n";
print OUT "\t\tpublic struct __mavlink_".$name."_t\n\t\t{\n";
$no = $1;
$start = 1;
#__mavlink_gps_raw_t
$structs[$no] = "__mavlink_".$name."_t";
} # __mavlink_heartbeat_t
$line =~ s/MAV_CMD_NAV_//;
$line =~ s/MAV_CMD_//;
if ($line =~ /<entry value="([0-9]+)" name="([^"]+)">/)
{
print OUT "\t\t\t$2 = $1,\n";
}
#<field type="uint8_t" name="type">
if ($line =~ /<field type="([^"]+)" name="([^"]+)">(.*)<\/field>/)
{
$type = $1;
$name = $2;
$desc = $3;
print "$type = $name\n";
$type =~ s/byte_mavlink_version/public byte/;
$type =~ s/array/public byte/;
$type =~ s/uint8_t/public byte/;
$type =~ s/int8_t/public byte/;
$type =~ s/float/public float/;
$type =~ s/uint16_t/public ushort/;
$type =~ s/uint32_t/public uint/;
$type =~ s/uint64_t/public ulong/;
$type =~ s/int16_t/public short/;
$type =~ s/int32_t/public int/;
$type =~ s/int64_t/public long/;
if ($type =~ /\[(.*)\]/) { # array
print OUT "\t\t\t[MarshalAs(UnmanagedType.ByValArray, SizeConst=". $1 .")] \n";
$type =~ s/\[.*\]//;
$type =~ s/public\s+([^\s]+)/public $1\[\]/o;
}
print OUT "\t\t\t$type $name; ///< $desc\n";
}
if ($start && ($line =~ /<\/message>/ || $line =~ /<\/enum>/)) {
print OUT "\t\t};\n\n";
$start = 0;
}
}
close(F);
}
print OUT "Type[] mavstructs = new Type[] {";
for ($a = 0; $a <= 256;$a++)
{
if (defined($structs[$a])) {
print OUT "typeof(".$structs[$a] .") ,";
} else {
print OUT "null ,";
}
}
print OUT "};\n\n";
print OUT <<EOF;
}
}
EOF
close OUT;
1;

View File

@ -1,12 +1,27 @@
$dir = "C:/Users/hog/Documents/Arduino/libraries/GCS_MAVLink/message_definitions/";
#$dir = "C:/Users/hog/Desktop/DIYDrones&avr/pixhawk-mavlink-c91adfb/include/common/";
$dir = "C:/Users/hog/Documents/Arduino/libraries/GCS_MAVLink/include/common/";
$dir2 = "C:/Users/hog/Documents/Arduino/libraries/GCS_MAVLink/include/ardupilotmega/";
# mavlink 1.0 with old structs
#$dir = "C:/Users/hog/Desktop/DIYDrones&avr/ardupilot-mega/libraries/GCS_MAVLink/include/common/";
#$dir2 = "C:/Users/hog/Desktop/DIYDrones&avr/ardupilot-mega/libraries/GCS_MAVLink/include/ardupilotmega/";
opendir(DIR,$dir) || die print $!;
@files2 = readdir(DIR);
closedir(DIR);
opendir(DIR,$dir2) || die print $!;
@files = readdir(DIR);
closedir(DIR);
push(@files,@files2);
push(@files,"../mavlink_types.h");
open(OUT,">MAVLinkTypes.cs");
$crcs = 0;
print OUT <<EOF;
using System;
using System.Collections.Generic;
@ -20,88 +35,72 @@ namespace ArdupilotMega
EOF
foreach $file (@files) {
if (!($file eq "common.xml" || $file eq "ardupilotmega.xml"))
{
print "$file\n";
if ($done{$file} == 1) {
next;
}
print "$file\n";
$done{$file} = 1;
open(F,$dir.$file);
open(F,$dir.$file) || open(F,$dir2.$file);
$start = 0;
while ($line = <F>) {
if ($line =~ /enum name="(MAV_.*)"/) {
$start = 1;
print OUT "\t\tpublic enum $1\n\t\t{ \n";
if ($line =~ /(MAVLINK_MESSAGE_LENGTHS|MAVLINK_MESSAGE_CRCS) (.*)/ && $crcs < 2) {
print OUT "\t\tpublic byte[] $1 = new byte[] $2;\n";
$crcs++;
}
if ($line =~ /<message id="([0-9]+)" name="([^"]+)">/) {
$name = lc($2);
print OUT "\t\tpublic const byte MAVLINK_MSG_ID_".uc($name) . " = " . $1 . ";\n";
print OUT "\t\t[StructLayout(LayoutKind.Sequential,Pack=1)]\n";
print OUT "\t\tpublic struct __mavlink_".$name."_t\n\t\t{\n";
$no = $1;
if ($line =~ /enum (MAV_.*)/) {
$start = 1;
print OUT "\t\tpublic ";
}
if ($line =~ /#define (MAVLINK_MSG_ID[^\s]+)\s+([0-9]+)/) {
print OUT "\t\tpublic const byte ".$1 . " = " . $2 . ";\n";
$no = $2;
}
if ($line =~ /typedef struct(.*)/) {
if ($1 =~ /__mavlink_system|param_union/) {
last;
}
$start = 1;
print OUT "\t\t[StructLayout(LayoutKind.Sequential,Pack=1)]\n";
#__mavlink_gps_raw_t
$structs[$no] = "__mavlink_".$name."_t";
} # __mavlink_heartbeat_t
$line =~ s/MAV_CMD_NAV_//;
$line =~ s/MAV_CMD_//;
if ($line =~ /<entry value="([0-9]+)" name="([^"]+)">/)
{
print OUT "\t\t\t$2 = $1,\n";
$structs[$no] = $1;
}
#<field type="uint8_t" name="type">
if ($line =~ /<field type="([^"]+)" name="([^"]+)">(.*)<\/field>/)
{
$type = $1;
$name = $2;
$desc = $3;
if ($start) {
$line =~ s/MAV_CMD_NAV_//;
print "$type = $name\n";
$line =~ s/MAV_CMD_//;
$type =~ s/byte_mavlink_version/public byte/;
$type =~ s/array/public byte/;
$line =~ s/typedef/public/;
$line =~ s/uint8_t/public byte/;
$line =~ s/int8_t/public byte/;
$line =~ s/^\s+float/public float/;
$line =~ s/uint16_t/public ushort/;
$line =~ s/uint32_t/public uint/;
$line =~ s/uint64_t/public ulong/;
$line =~ s/int16_t/public short/;
$line =~ s/int32_t/public int/;
$line =~ s/int64_t/public long/;
$line =~ s/typedef/public/;
$line =~ s/}.*/};\n/;
$type =~ s/uint8_t/public byte/;
$type =~ s/int8_t/public byte/;
$type =~ s/float/public float/;
$type =~ s/uint16_t/public ushort/;
$type =~ s/uint32_t/public uint/;
$type =~ s/uint64_t/public ulong/;
$type =~ s/int16_t/public short/;
$type =~ s/int32_t/public int/;
$type =~ s/int64_t/public long/;
if ($type =~ /\[(.*)\]/) { # array
print OUT "\t\t\t[MarshalAs(UnmanagedType.ByValArray, SizeConst=". $1 .")] \n";
$type =~ s/\[.*\]//;
$type =~ s/public\s+([^\s]+)/public $1\[\]/o;
}
if ($line =~ /\[(.*)\].*;/) { # array
print OUT "\t\t[MarshalAs(
UnmanagedType.ByValArray,
SizeConst=". $1 .")] \n";
$line =~ s/\[.*\]//;
$line =~ s/public\s+([^\s]+)/public $1\[\]/o;
}
print OUT "\t\t\t$type $name; ///< $desc\n";
}
if ($start && ($line =~ /<\/message>/ || $line =~ /<\/enum>/)) {
print OUT "\t\t};\n\n";
print OUT "\t\t".$line;
}
if ($line =~ /}/) {
$start = 0;
}
@ -129,4 +128,6 @@ EOF
close OUT;
<STDIN>;
1;

View File

@ -14,7 +14,7 @@ namespace ArdupilotMega
{
short alt = -32768;
lat += 0.0008;
lat += 0.00083333333333333;
//lng += 0.0008;
int x = (int)Math.Floor(lng);
@ -32,44 +32,139 @@ namespace ArdupilotMega
else
ew = "W";
string filename = ns+ Math.Abs(y).ToString("00")+ew+ Math.Abs(x).ToString("000")+".hgt";
string filename = ns + Math.Abs(y).ToString("00") + ew + Math.Abs(x).ToString("000") + ".hgt";
string filename2 = "srtm_" + Math.Round((lng + 2.5 + 180) / 5, 0).ToString("00") + "_" + Math.Round((60 - lat + 2.5) / 5, 0).ToString("00") + ".asc";
if (File.Exists(datadirectory + Path.DirectorySeparatorChar + filename))
{ // srtm hgt files
FileStream fs = new FileStream(datadirectory + Path.DirectorySeparatorChar + filename, FileMode.Open, FileAccess.Read);
float posx = 0;
float row = 0;
if (fs.Length <= (1201 * 1201 * 2))
{
posx = (int)(((float)(lng - x)) * (1201 * 2));
row = (int)(((float)(lat - y)) * 1201) * (1201 * 2);
row = (1201 * 1201 * 2) - row;
}
else
{
posx = (int)(((float)(lng - x)) * (3601 * 2));
row = (int)(((float)(lat - y)) * 3601) * (3601 * 2);
row = (3601 * 3601 * 2) - row;
}
if (posx % 2 == 1)
{
posx--;
}
//Console.WriteLine(filename + " row " + row + " posx" + posx);
byte[] data = new byte[2];
fs.Seek((int)(row + posx), SeekOrigin.Begin);
fs.Read(data, 0, data.Length);
fs.Close();
fs.Dispose();
Array.Reverse(data);
alt = BitConverter.ToInt16(data, 0);
if (!File.Exists(datadirectory + Path.DirectorySeparatorChar + filename))
{
return alt;
}
FileStream fs = new FileStream(datadirectory + Path.DirectorySeparatorChar + filename, FileMode.Open,FileAccess.Read);
float posx = 0;
float row = 0;
if (fs.Length <= (1201 * 1201 * 2)) {
posx = (int)(((float)(lng - x)) * (1201 * 2));
row = (int)(((float)(lat - y)) * 1201) * (1201 * 2);
row = (1201 * 1201 * 2) - row;
} else {
posx = (int)(((float)(lng - x)) * (3601 * 2));
row = (int)(((float)(lat - y)) * 3601) * (3601 * 2);
row = (3601 * 3601 * 2) - row;
}
if (posx % 2 == 1)
else if (File.Exists(datadirectory + Path.DirectorySeparatorChar + filename2))
{
posx--;
// this is way to slow - and cacheing it will chew memory 6001 * 6001 * 4 = 144048004 bytes
FileStream fs = new FileStream(datadirectory + Path.DirectorySeparatorChar + filename2, FileMode.Open, FileAccess.Read);
StreamReader sr = new StreamReader(fs);
int nox = 0;
int noy = 0;
float left = 0;
float top = 0;
int nodata = -9999;
float cellsize = 0;
int rowcounter = 0;
float wantrow = 0;
float wantcol = 0;
while (!sr.EndOfStream)
{
string line = sr.ReadLine();
if (line.StartsWith("ncols"))
{
nox = int.Parse(line.Substring(line.IndexOf(' ')));
//hgtdata = new int[nox * noy];
}
else if (line.StartsWith("nrows"))
{
noy = int.Parse(line.Substring(line.IndexOf(' ')));
//hgtdata = new int[nox * noy];
}
else if (line.StartsWith("xllcorner"))
{
left = float.Parse(line.Substring(line.IndexOf(' ')));
}
else if (line.StartsWith("yllcorner"))
{
top = float.Parse(line.Substring(line.IndexOf(' ')));
}
else if (line.StartsWith("cellsize"))
{
cellsize = float.Parse(line.Substring(line.IndexOf(' ')));
}
else if (line.StartsWith("NODATA_value"))
{
nodata = int.Parse(line.Substring(line.IndexOf(' ')));
}
else
{
string[] data = line.Split(new char[] { ' ' });
if (data.Length == (nox + 1))
{
wantcol = (float)((lng - Math.Round(left,0)));
wantrow = (float)((lat - Math.Round(top,0)));
wantrow =(int)( wantrow / cellsize);
wantcol =(int)( wantcol / cellsize);
wantrow = noy - wantrow;
if (rowcounter == wantrow)
{
Console.WriteLine("{0} {1} {2} {3} ans {4} x {5}", lng, lat, left, top, data[(int)wantcol], (nox + wantcol * cellsize));
return int.Parse(data[(int)wantcol]);
}
rowcounter++;
}
}
}
return alt;
}
//Console.WriteLine(filename + " row " + row + " posx" + posx);
byte[] data = new byte[2];
fs.Seek((int)(row + posx), SeekOrigin.Begin);
fs.Read(data, 0, data.Length);
Array.Reverse(data);
alt = BitConverter.ToInt16(data,0);
return alt;
}
}