mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 22:18:29 -04:00
Configurator.Net: Added GPS status view
git-svn-id: https://arducopter.googlecode.com/svn/trunk@1731 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
342c60e748
commit
13159421df
@ -72,6 +72,7 @@
|
|||||||
<Compile Include="PresentationModels\AltitudeHoldConfigVm.cs" />
|
<Compile Include="PresentationModels\AltitudeHoldConfigVm.cs" />
|
||||||
<Compile Include="PresentationModels\ConfigWithPidsBase.cs" />
|
<Compile Include="PresentationModels\ConfigWithPidsBase.cs" />
|
||||||
<Compile Include="Core\DelegateCommand.cs" />
|
<Compile Include="Core\DelegateCommand.cs" />
|
||||||
|
<Compile Include="PresentationModels\GPSstatusVm.cs" />
|
||||||
<Compile Include="PresentationModels\CrudVm.cs" />
|
<Compile Include="PresentationModels\CrudVm.cs" />
|
||||||
<Compile Include="PresentationModels\DoubleVm.cs" />
|
<Compile Include="PresentationModels\DoubleVm.cs" />
|
||||||
<Compile Include="PresentationModels\PositionAltitudePidsVm.cs" />
|
<Compile Include="PresentationModels\PositionAltitudePidsVm.cs" />
|
||||||
@ -104,6 +105,12 @@
|
|||||||
<Compile Include="Views\controls\LinearIndicatorControl.Designer.cs">
|
<Compile Include="Views\controls\LinearIndicatorControl.Designer.cs">
|
||||||
<DependentUpon>LinearIndicatorControl.cs</DependentUpon>
|
<DependentUpon>LinearIndicatorControl.cs</DependentUpon>
|
||||||
</Compile>
|
</Compile>
|
||||||
|
<Compile Include="Views\GpsView.cs">
|
||||||
|
<SubType>UserControl</SubType>
|
||||||
|
</Compile>
|
||||||
|
<Compile Include="Views\GpsView.Designer.cs">
|
||||||
|
<DependentUpon>GpsView.cs</DependentUpon>
|
||||||
|
</Compile>
|
||||||
<Compile Include="Views\PositionAltitudePidsView.cs">
|
<Compile Include="Views\PositionAltitudePidsView.cs">
|
||||||
<SubType>UserControl</SubType>
|
<SubType>UserControl</SubType>
|
||||||
</Compile>
|
</Compile>
|
||||||
@ -246,6 +253,9 @@
|
|||||||
<EmbeddedResource Include="Views\controls\QuadPlanControl.resx">
|
<EmbeddedResource Include="Views\controls\QuadPlanControl.resx">
|
||||||
<DependentUpon>QuadPlanControl.cs</DependentUpon>
|
<DependentUpon>QuadPlanControl.cs</DependentUpon>
|
||||||
</EmbeddedResource>
|
</EmbeddedResource>
|
||||||
|
<EmbeddedResource Include="Views\GpsView.resx">
|
||||||
|
<DependentUpon>GpsView.cs</DependentUpon>
|
||||||
|
</EmbeddedResource>
|
||||||
<EmbeddedResource Include="Views\PositionAltitudePidsView.resx">
|
<EmbeddedResource Include="Views\PositionAltitudePidsView.resx">
|
||||||
<DependentUpon>PositionAltitudePidsView.cs</DependentUpon>
|
<DependentUpon>PositionAltitudePidsView.cs</DependentUpon>
|
||||||
</EmbeddedResource>
|
</EmbeddedResource>
|
||||||
|
218
Configurator/Configurator.Net/PresentationModels/GPSstatusVm.cs
Normal file
218
Configurator/Configurator.Net/PresentationModels/GPSstatusVm.cs
Normal file
@ -0,0 +1,218 @@
|
|||||||
|
using System;
|
||||||
|
using System.ComponentModel;
|
||||||
|
using System.Drawing;
|
||||||
|
using System.Globalization;
|
||||||
|
using System.IO;
|
||||||
|
using System.Net;
|
||||||
|
|
||||||
|
namespace ArducopterConfigurator.PresentationModels
|
||||||
|
{
|
||||||
|
public class GpsStatusVm : NotifyProperyChangedBase, IPresentationModel
|
||||||
|
{
|
||||||
|
private const string SEND_GPS_DATA = "4";
|
||||||
|
private const string STOP_UPDATES = "X";
|
||||||
|
|
||||||
|
public ICommand GetMapCommand { get; private set; }
|
||||||
|
|
||||||
|
private BackgroundWorker bg;
|
||||||
|
|
||||||
|
public GpsStatusVm()
|
||||||
|
{
|
||||||
|
bg = new BackgroundWorker();
|
||||||
|
bg.DoWork += DownloadGoogleMap;
|
||||||
|
bg.RunWorkerCompleted += DownloadGoogleMapComplete;
|
||||||
|
|
||||||
|
GetMapCommand = new DelegateCommand(_ => GetMap(), _=> HasFix && !bg.IsBusy);
|
||||||
|
}
|
||||||
|
|
||||||
|
private void GetMap()
|
||||||
|
{
|
||||||
|
var urlTemplate =
|
||||||
|
"http://maps.google.com/maps/api/staticmap?&markers=color:blue|label:A|{0:0.00000},{1:0.00000}&zoom=13&size=250x200&maptype=roadmap&sensor=false";
|
||||||
|
|
||||||
|
var url = string.Format(CultureInfo.InvariantCulture, urlTemplate, GpsLatitude, GpsLongitude);
|
||||||
|
|
||||||
|
bg.RunWorkerAsync(url);
|
||||||
|
}
|
||||||
|
|
||||||
|
private void DownloadGoogleMapComplete(object sender, RunWorkerCompletedEventArgs e)
|
||||||
|
{
|
||||||
|
MapImage = e.Result as Image;
|
||||||
|
}
|
||||||
|
|
||||||
|
private void DownloadGoogleMap(object sender, DoWorkEventArgs e)
|
||||||
|
{
|
||||||
|
var url = e.Argument as string;
|
||||||
|
var Client = new WebClient();
|
||||||
|
using (var strm = Client.OpenRead(url))
|
||||||
|
{
|
||||||
|
var png = Image.FromStream(strm);
|
||||||
|
e.Result = png;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
private void sendString(string str)
|
||||||
|
{
|
||||||
|
if (sendTextToApm != null)
|
||||||
|
sendTextToApm(this, new sendTextToApmEventArgs(str));
|
||||||
|
}
|
||||||
|
|
||||||
|
public void Activate()
|
||||||
|
{
|
||||||
|
sendString(SEND_GPS_DATA);
|
||||||
|
}
|
||||||
|
|
||||||
|
public void DeActivate()
|
||||||
|
{
|
||||||
|
sendString(STOP_UPDATES);
|
||||||
|
}
|
||||||
|
|
||||||
|
public event EventHandler updatedByApm;
|
||||||
|
|
||||||
|
|
||||||
|
public string Name
|
||||||
|
{
|
||||||
|
get { return "GPS Status"; }
|
||||||
|
}
|
||||||
|
|
||||||
|
public void handleLineOfText(string strRx)
|
||||||
|
{
|
||||||
|
// We don't bother with the automatic property population, as the received string is
|
||||||
|
// tab delimeted and the values have crazy scale factors anyway.
|
||||||
|
|
||||||
|
// hack for testing with no GPS
|
||||||
|
// strRx = "73410000\t407021470\t-740157940\t9242\t0\t19831\t1";
|
||||||
|
|
||||||
|
var parts = strRx.Split('\t');
|
||||||
|
try
|
||||||
|
{
|
||||||
|
GpsTime = int.Parse(parts[0].Trim(), CultureInfo.InvariantCulture);
|
||||||
|
GpsLatitude = (float)(int.Parse(parts[1].Trim(), CultureInfo.InvariantCulture)) / 10000000;
|
||||||
|
GpsLongitude = (float)(int.Parse(parts[2].Trim(), CultureInfo.InvariantCulture)) / 10000000;
|
||||||
|
GpsAltitude = int.Parse(parts[3].Trim(), CultureInfo.InvariantCulture) / 100;
|
||||||
|
GpsGroundSpeed = (float)(int.Parse(parts[4].Trim(), CultureInfo.InvariantCulture)) / 100;
|
||||||
|
GpsGroundCourse = int.Parse(parts[5].Trim(), CultureInfo.InvariantCulture) / 100;
|
||||||
|
HasFix = parts[6].Trim() == "1";
|
||||||
|
|
||||||
|
// Todo: the number of sats is actually a raw char, not an ascii char like '3'
|
||||||
|
}
|
||||||
|
catch (FormatException)
|
||||||
|
{
|
||||||
|
Console.WriteLine("Format Exception in GPS VM, string: " + strRx);
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
public event EventHandler<sendTextToApmEventArgs> sendTextToApm;
|
||||||
|
|
||||||
|
#region bindables
|
||||||
|
|
||||||
|
private Image _mapImage;
|
||||||
|
|
||||||
|
public Image MapImage
|
||||||
|
{
|
||||||
|
get { return _mapImage; }
|
||||||
|
set
|
||||||
|
{
|
||||||
|
if (_mapImage == value) return;
|
||||||
|
_mapImage = value;
|
||||||
|
FirePropertyChanged("MapImage");
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
private int _gpsTime;
|
||||||
|
|
||||||
|
public int GpsTime
|
||||||
|
{
|
||||||
|
get { return _gpsTime; }
|
||||||
|
set
|
||||||
|
{
|
||||||
|
if (_gpsTime == value) return;
|
||||||
|
_gpsTime = value;
|
||||||
|
FirePropertyChanged("GpsTime");
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
private float _gpsLatitude;
|
||||||
|
|
||||||
|
public float GpsLatitude
|
||||||
|
{
|
||||||
|
get { return _gpsLatitude; }
|
||||||
|
set
|
||||||
|
{
|
||||||
|
if (_gpsLatitude == value) return;
|
||||||
|
_gpsLatitude = value;
|
||||||
|
FirePropertyChanged("GpsLatitude");
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
private float _gpsLongitude;
|
||||||
|
|
||||||
|
public float GpsLongitude
|
||||||
|
{
|
||||||
|
get { return _gpsLongitude; }
|
||||||
|
set
|
||||||
|
{
|
||||||
|
if (_gpsLongitude == value) return;
|
||||||
|
_gpsLongitude = value;
|
||||||
|
FirePropertyChanged("GpsLongitude");
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
private float _gpsGroundSpeed;
|
||||||
|
|
||||||
|
public float GpsGroundSpeed
|
||||||
|
{
|
||||||
|
get { return _gpsGroundSpeed; }
|
||||||
|
set
|
||||||
|
{
|
||||||
|
if (_gpsGroundSpeed == value) return;
|
||||||
|
_gpsGroundSpeed = value;
|
||||||
|
FirePropertyChanged("GpsGroundSpeed");
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
private int _gpsGroundCourse;
|
||||||
|
|
||||||
|
public int GpsGroundCourse
|
||||||
|
{
|
||||||
|
get { return _gpsGroundCourse; }
|
||||||
|
set
|
||||||
|
{
|
||||||
|
if (_gpsGroundCourse == value) return;
|
||||||
|
_gpsGroundCourse = value;
|
||||||
|
FirePropertyChanged("GpsGroundCourse");
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
private int _gpsAltitude;
|
||||||
|
|
||||||
|
public int GpsAltitude
|
||||||
|
{
|
||||||
|
get { return _gpsAltitude; }
|
||||||
|
set
|
||||||
|
{
|
||||||
|
if (_gpsAltitude == value) return;
|
||||||
|
_gpsAltitude = value;
|
||||||
|
FirePropertyChanged("GpsAltitude");
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
private bool _hasFix;
|
||||||
|
|
||||||
|
public bool HasFix
|
||||||
|
{
|
||||||
|
get { return _hasFix; }
|
||||||
|
set
|
||||||
|
{
|
||||||
|
if (_hasFix == value) return;
|
||||||
|
_hasFix = value;
|
||||||
|
FirePropertyChanged("HasFix");
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
#endregion
|
||||||
|
}
|
||||||
|
}
|
@ -27,8 +27,10 @@ namespace ArducopterConfigurator.PresentationModels
|
|||||||
new TransmitterChannelsVm(),
|
new TransmitterChannelsVm(),
|
||||||
new FlightControlPidsVm(),
|
new FlightControlPidsVm(),
|
||||||
new PositionAltitudePidsVm(),
|
new PositionAltitudePidsVm(),
|
||||||
|
new GpsStatusVm(),
|
||||||
|
|
||||||
//new MotorCommandsVm(session),
|
//new MotorCommandsVm(session),
|
||||||
new SerialMonitorVm()
|
new SerialMonitorVm(),
|
||||||
};
|
};
|
||||||
|
|
||||||
foreach (var vm in MonitorVms)
|
foreach (var vm in MonitorVms)
|
||||||
|
250
Configurator/Configurator.Net/Views/GpsView.Designer.cs
generated
Normal file
250
Configurator/Configurator.Net/Views/GpsView.Designer.cs
generated
Normal file
@ -0,0 +1,250 @@
|
|||||||
|
namespace ArducopterConfigurator.Views
|
||||||
|
{
|
||||||
|
partial class GpsStatusView
|
||||||
|
{
|
||||||
|
/// <summary>
|
||||||
|
/// Required designer variable.
|
||||||
|
/// </summary>
|
||||||
|
private System.ComponentModel.IContainer components = null;
|
||||||
|
|
||||||
|
/// <summary>
|
||||||
|
/// Clean up any resources being used.
|
||||||
|
/// </summary>
|
||||||
|
/// <param name="disposing">true if managed resources should be disposed; otherwise, false.</param>
|
||||||
|
protected override void Dispose(bool disposing)
|
||||||
|
{
|
||||||
|
if (disposing && (components != null))
|
||||||
|
{
|
||||||
|
components.Dispose();
|
||||||
|
}
|
||||||
|
base.Dispose(disposing);
|
||||||
|
}
|
||||||
|
|
||||||
|
#region Component Designer generated code
|
||||||
|
|
||||||
|
/// <summary>
|
||||||
|
/// Required method for Designer support - do not modify
|
||||||
|
/// the contents of this method with the code editor.
|
||||||
|
/// </summary>
|
||||||
|
private void InitializeComponent()
|
||||||
|
{
|
||||||
|
this.components = new System.ComponentModel.Container();
|
||||||
|
this.GpsStatusBindingSource = new System.Windows.Forms.BindingSource(this.components);
|
||||||
|
this.textBox7 = new System.Windows.Forms.TextBox();
|
||||||
|
this.label1 = new System.Windows.Forms.Label();
|
||||||
|
this.label2 = new System.Windows.Forms.Label();
|
||||||
|
this.textBox1 = new System.Windows.Forms.TextBox();
|
||||||
|
this.label3 = new System.Windows.Forms.Label();
|
||||||
|
this.textBox2 = new System.Windows.Forms.TextBox();
|
||||||
|
this.label4 = new System.Windows.Forms.Label();
|
||||||
|
this.textBox3 = new System.Windows.Forms.TextBox();
|
||||||
|
this.label5 = new System.Windows.Forms.Label();
|
||||||
|
this.textBox4 = new System.Windows.Forms.TextBox();
|
||||||
|
this.label6 = new System.Windows.Forms.Label();
|
||||||
|
this.label7 = new System.Windows.Forms.Label();
|
||||||
|
this.button1 = new System.Windows.Forms.Button();
|
||||||
|
this.pictureBox1 = new System.Windows.Forms.PictureBox();
|
||||||
|
((System.ComponentModel.ISupportInitialize)(this.GpsStatusBindingSource)).BeginInit();
|
||||||
|
((System.ComponentModel.ISupportInitialize)(this.pictureBox1)).BeginInit();
|
||||||
|
this.SuspendLayout();
|
||||||
|
//
|
||||||
|
// GpsStatusBindingSource
|
||||||
|
//
|
||||||
|
this.GpsStatusBindingSource.DataSource = typeof(ArducopterConfigurator.PresentationModels.GpsStatusVm);
|
||||||
|
//
|
||||||
|
// textBox7
|
||||||
|
//
|
||||||
|
this.textBox7.BorderStyle = System.Windows.Forms.BorderStyle.None;
|
||||||
|
this.textBox7.DataBindings.Add(new System.Windows.Forms.Binding("Text", this.GpsStatusBindingSource, "GpsLongitude", true, System.Windows.Forms.DataSourceUpdateMode.Never, null, "N4"));
|
||||||
|
this.textBox7.DataBindings.Add(new System.Windows.Forms.Binding("Visible", this.GpsStatusBindingSource, "HasFix", true, System.Windows.Forms.DataSourceUpdateMode.Never));
|
||||||
|
this.textBox7.Enabled = false;
|
||||||
|
this.textBox7.Location = new System.Drawing.Point(88, 24);
|
||||||
|
this.textBox7.Name = "textBox7";
|
||||||
|
this.textBox7.ReadOnly = true;
|
||||||
|
this.textBox7.Size = new System.Drawing.Size(53, 13);
|
||||||
|
this.textBox7.TabIndex = 24;
|
||||||
|
this.textBox7.TextAlign = System.Windows.Forms.HorizontalAlignment.Center;
|
||||||
|
//
|
||||||
|
// label1
|
||||||
|
//
|
||||||
|
this.label1.AutoSize = true;
|
||||||
|
this.label1.Location = new System.Drawing.Point(4, 24);
|
||||||
|
this.label1.Name = "label1";
|
||||||
|
this.label1.Size = new System.Drawing.Size(54, 13);
|
||||||
|
this.label1.TabIndex = 25;
|
||||||
|
this.label1.Text = "Longitude";
|
||||||
|
//
|
||||||
|
// label2
|
||||||
|
//
|
||||||
|
this.label2.AutoSize = true;
|
||||||
|
this.label2.Location = new System.Drawing.Point(4, 46);
|
||||||
|
this.label2.Name = "label2";
|
||||||
|
this.label2.Size = new System.Drawing.Size(45, 13);
|
||||||
|
this.label2.TabIndex = 27;
|
||||||
|
this.label2.Text = "Latitude";
|
||||||
|
//
|
||||||
|
// textBox1
|
||||||
|
//
|
||||||
|
this.textBox1.BorderStyle = System.Windows.Forms.BorderStyle.None;
|
||||||
|
this.textBox1.DataBindings.Add(new System.Windows.Forms.Binding("Text", this.GpsStatusBindingSource, "GpsLatitude", true, System.Windows.Forms.DataSourceUpdateMode.Never, null, "N4"));
|
||||||
|
this.textBox1.DataBindings.Add(new System.Windows.Forms.Binding("Visible", this.GpsStatusBindingSource, "HasFix", true, System.Windows.Forms.DataSourceUpdateMode.Never));
|
||||||
|
this.textBox1.Enabled = false;
|
||||||
|
this.textBox1.Location = new System.Drawing.Point(88, 46);
|
||||||
|
this.textBox1.Name = "textBox1";
|
||||||
|
this.textBox1.ReadOnly = true;
|
||||||
|
this.textBox1.Size = new System.Drawing.Size(53, 13);
|
||||||
|
this.textBox1.TabIndex = 26;
|
||||||
|
this.textBox1.TextAlign = System.Windows.Forms.HorizontalAlignment.Center;
|
||||||
|
//
|
||||||
|
// label3
|
||||||
|
//
|
||||||
|
this.label3.AutoSize = true;
|
||||||
|
this.label3.Location = new System.Drawing.Point(4, 68);
|
||||||
|
this.label3.Name = "label3";
|
||||||
|
this.label3.Size = new System.Drawing.Size(42, 13);
|
||||||
|
this.label3.TabIndex = 29;
|
||||||
|
this.label3.Text = "Altitude";
|
||||||
|
//
|
||||||
|
// textBox2
|
||||||
|
//
|
||||||
|
this.textBox2.BorderStyle = System.Windows.Forms.BorderStyle.None;
|
||||||
|
this.textBox2.DataBindings.Add(new System.Windows.Forms.Binding("Text", this.GpsStatusBindingSource, "GpsAltitude", true, System.Windows.Forms.DataSourceUpdateMode.Never, null, "N0"));
|
||||||
|
this.textBox2.DataBindings.Add(new System.Windows.Forms.Binding("Visible", this.GpsStatusBindingSource, "HasFix", true, System.Windows.Forms.DataSourceUpdateMode.Never));
|
||||||
|
this.textBox2.Enabled = false;
|
||||||
|
this.textBox2.Location = new System.Drawing.Point(88, 68);
|
||||||
|
this.textBox2.Name = "textBox2";
|
||||||
|
this.textBox2.ReadOnly = true;
|
||||||
|
this.textBox2.Size = new System.Drawing.Size(35, 13);
|
||||||
|
this.textBox2.TabIndex = 28;
|
||||||
|
this.textBox2.TextAlign = System.Windows.Forms.HorizontalAlignment.Center;
|
||||||
|
//
|
||||||
|
// label4
|
||||||
|
//
|
||||||
|
this.label4.AutoSize = true;
|
||||||
|
this.label4.Location = new System.Drawing.Point(4, 90);
|
||||||
|
this.label4.Name = "label4";
|
||||||
|
this.label4.Size = new System.Drawing.Size(76, 13);
|
||||||
|
this.label4.TabIndex = 31;
|
||||||
|
this.label4.Text = "Ground Speed";
|
||||||
|
//
|
||||||
|
// textBox3
|
||||||
|
//
|
||||||
|
this.textBox3.BorderStyle = System.Windows.Forms.BorderStyle.None;
|
||||||
|
this.textBox3.DataBindings.Add(new System.Windows.Forms.Binding("Text", this.GpsStatusBindingSource, "GpsGroundSpeed", true, System.Windows.Forms.DataSourceUpdateMode.Never, null, "N2"));
|
||||||
|
this.textBox3.DataBindings.Add(new System.Windows.Forms.Binding("Visible", this.GpsStatusBindingSource, "HasFix", true, System.Windows.Forms.DataSourceUpdateMode.Never));
|
||||||
|
this.textBox3.Enabled = false;
|
||||||
|
this.textBox3.Location = new System.Drawing.Point(88, 90);
|
||||||
|
this.textBox3.Name = "textBox3";
|
||||||
|
this.textBox3.ReadOnly = true;
|
||||||
|
this.textBox3.Size = new System.Drawing.Size(35, 13);
|
||||||
|
this.textBox3.TabIndex = 30;
|
||||||
|
this.textBox3.TextAlign = System.Windows.Forms.HorizontalAlignment.Center;
|
||||||
|
//
|
||||||
|
// label5
|
||||||
|
//
|
||||||
|
this.label5.AutoSize = true;
|
||||||
|
this.label5.Location = new System.Drawing.Point(4, 112);
|
||||||
|
this.label5.Name = "label5";
|
||||||
|
this.label5.Size = new System.Drawing.Size(78, 13);
|
||||||
|
this.label5.TabIndex = 33;
|
||||||
|
this.label5.Text = "Ground Course";
|
||||||
|
//
|
||||||
|
// textBox4
|
||||||
|
//
|
||||||
|
this.textBox4.BorderStyle = System.Windows.Forms.BorderStyle.None;
|
||||||
|
this.textBox4.DataBindings.Add(new System.Windows.Forms.Binding("Text", this.GpsStatusBindingSource, "GpsGroundCourse", true, System.Windows.Forms.DataSourceUpdateMode.Never, null, "N0"));
|
||||||
|
this.textBox4.DataBindings.Add(new System.Windows.Forms.Binding("Visible", this.GpsStatusBindingSource, "HasFix", true, System.Windows.Forms.DataSourceUpdateMode.Never));
|
||||||
|
this.textBox4.Enabled = false;
|
||||||
|
this.textBox4.Location = new System.Drawing.Point(88, 112);
|
||||||
|
this.textBox4.Name = "textBox4";
|
||||||
|
this.textBox4.ReadOnly = true;
|
||||||
|
this.textBox4.Size = new System.Drawing.Size(35, 13);
|
||||||
|
this.textBox4.TabIndex = 32;
|
||||||
|
this.textBox4.TextAlign = System.Windows.Forms.HorizontalAlignment.Center;
|
||||||
|
//
|
||||||
|
// label6
|
||||||
|
//
|
||||||
|
this.label6.AutoSize = true;
|
||||||
|
this.label6.ForeColor = System.Drawing.Color.Red;
|
||||||
|
this.label6.Location = new System.Drawing.Point(32, 137);
|
||||||
|
this.label6.Name = "label6";
|
||||||
|
this.label6.Size = new System.Drawing.Size(62, 13);
|
||||||
|
this.label6.TabIndex = 34;
|
||||||
|
this.label6.Text = "No GPS Fix";
|
||||||
|
//
|
||||||
|
// label7
|
||||||
|
//
|
||||||
|
this.label7.AutoSize = true;
|
||||||
|
this.label7.DataBindings.Add(new System.Windows.Forms.Binding("Visible", this.GpsStatusBindingSource, "HasFix", true, System.Windows.Forms.DataSourceUpdateMode.Never));
|
||||||
|
this.label7.Location = new System.Drawing.Point(32, 137);
|
||||||
|
this.label7.Name = "label7";
|
||||||
|
this.label7.Size = new System.Drawing.Size(84, 13);
|
||||||
|
this.label7.TabIndex = 35;
|
||||||
|
this.label7.Text = "GPS Fix Aquired";
|
||||||
|
//
|
||||||
|
// button1
|
||||||
|
//
|
||||||
|
this.button1.DataBindings.Add(new System.Windows.Forms.Binding("Tag", this.GpsStatusBindingSource, "GetMapCommand", true));
|
||||||
|
this.button1.Location = new System.Drawing.Point(7, 162);
|
||||||
|
this.button1.Name = "button1";
|
||||||
|
this.button1.Size = new System.Drawing.Size(75, 23);
|
||||||
|
this.button1.TabIndex = 36;
|
||||||
|
this.button1.Text = "Get Map";
|
||||||
|
this.button1.UseVisualStyleBackColor = true;
|
||||||
|
//
|
||||||
|
// pictureBox1
|
||||||
|
//
|
||||||
|
this.pictureBox1.BorderStyle = System.Windows.Forms.BorderStyle.FixedSingle;
|
||||||
|
this.pictureBox1.DataBindings.Add(new System.Windows.Forms.Binding("Image", this.GpsStatusBindingSource, "MapImage", true));
|
||||||
|
this.pictureBox1.Location = new System.Drawing.Point(164, 24);
|
||||||
|
this.pictureBox1.Name = "pictureBox1";
|
||||||
|
this.pictureBox1.Size = new System.Drawing.Size(250, 200);
|
||||||
|
this.pictureBox1.TabIndex = 37;
|
||||||
|
this.pictureBox1.TabStop = false;
|
||||||
|
//
|
||||||
|
// GpsStatusView
|
||||||
|
//
|
||||||
|
this.AutoScaleDimensions = new System.Drawing.SizeF(6F, 13F);
|
||||||
|
this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font;
|
||||||
|
this.Controls.Add(this.pictureBox1);
|
||||||
|
this.Controls.Add(this.button1);
|
||||||
|
this.Controls.Add(this.label7);
|
||||||
|
this.Controls.Add(this.label6);
|
||||||
|
this.Controls.Add(this.label5);
|
||||||
|
this.Controls.Add(this.textBox4);
|
||||||
|
this.Controls.Add(this.label4);
|
||||||
|
this.Controls.Add(this.textBox3);
|
||||||
|
this.Controls.Add(this.label3);
|
||||||
|
this.Controls.Add(this.textBox2);
|
||||||
|
this.Controls.Add(this.label2);
|
||||||
|
this.Controls.Add(this.textBox1);
|
||||||
|
this.Controls.Add(this.label1);
|
||||||
|
this.Controls.Add(this.textBox7);
|
||||||
|
this.Name = "GpsStatusView";
|
||||||
|
this.Size = new System.Drawing.Size(440, 300);
|
||||||
|
((System.ComponentModel.ISupportInitialize)(this.GpsStatusBindingSource)).EndInit();
|
||||||
|
((System.ComponentModel.ISupportInitialize)(this.pictureBox1)).EndInit();
|
||||||
|
this.ResumeLayout(false);
|
||||||
|
this.PerformLayout();
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
#endregion
|
||||||
|
|
||||||
|
private System.Windows.Forms.BindingSource GpsStatusBindingSource;
|
||||||
|
private System.Windows.Forms.TextBox textBox7;
|
||||||
|
private System.Windows.Forms.Label label1;
|
||||||
|
private System.Windows.Forms.Label label2;
|
||||||
|
private System.Windows.Forms.TextBox textBox1;
|
||||||
|
private System.Windows.Forms.Label label3;
|
||||||
|
private System.Windows.Forms.TextBox textBox2;
|
||||||
|
private System.Windows.Forms.Label label4;
|
||||||
|
private System.Windows.Forms.TextBox textBox3;
|
||||||
|
private System.Windows.Forms.Label label5;
|
||||||
|
private System.Windows.Forms.TextBox textBox4;
|
||||||
|
private System.Windows.Forms.Label label6;
|
||||||
|
private System.Windows.Forms.Label label7;
|
||||||
|
private System.Windows.Forms.Button button1;
|
||||||
|
private System.Windows.Forms.PictureBox pictureBox1;
|
||||||
|
}
|
||||||
|
}
|
34
Configurator/Configurator.Net/Views/GpsView.cs
Normal file
34
Configurator/Configurator.Net/Views/GpsView.cs
Normal file
@ -0,0 +1,34 @@
|
|||||||
|
using System;
|
||||||
|
using System.Collections.Generic;
|
||||||
|
using System.ComponentModel;
|
||||||
|
using System.Drawing;
|
||||||
|
using System.Data;
|
||||||
|
using System.Text;
|
||||||
|
using System.Windows.Forms;
|
||||||
|
using ArducopterConfigurator.PresentationModels;
|
||||||
|
|
||||||
|
namespace ArducopterConfigurator.Views
|
||||||
|
{
|
||||||
|
public partial class GpsStatusView : GpsViewDesignable
|
||||||
|
{
|
||||||
|
public GpsStatusView()
|
||||||
|
{
|
||||||
|
InitializeComponent();
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
public override void SetDataContext(GpsStatusVm vm)
|
||||||
|
{
|
||||||
|
BindButtons(vm);
|
||||||
|
|
||||||
|
GpsStatusBindingSource.DataSource = vm;
|
||||||
|
|
||||||
|
if (Program.IsMonoRuntime)
|
||||||
|
vm.PropertyChanged += ((sender, e) => GpsStatusBindingSource.ResetBindings(false));
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
// Required for VS2008 designer. No functional value
|
||||||
|
public class GpsViewDesignable : ViewCommon<GpsStatusVm> { }
|
||||||
|
}
|
123
Configurator/Configurator.Net/Views/GpsView.resx
Normal file
123
Configurator/Configurator.Net/Views/GpsView.resx
Normal file
@ -0,0 +1,123 @@
|
|||||||
|
<?xml version="1.0" encoding="utf-8"?>
|
||||||
|
<root>
|
||||||
|
<!--
|
||||||
|
Microsoft ResX Schema
|
||||||
|
|
||||||
|
Version 2.0
|
||||||
|
|
||||||
|
The primary goals of this format is to allow a simple XML format
|
||||||
|
that is mostly human readable. The generation and parsing of the
|
||||||
|
various data types are done through the TypeConverter classes
|
||||||
|
associated with the data types.
|
||||||
|
|
||||||
|
Example:
|
||||||
|
|
||||||
|
... ado.net/XML headers & schema ...
|
||||||
|
<resheader name="resmimetype">text/microsoft-resx</resheader>
|
||||||
|
<resheader name="version">2.0</resheader>
|
||||||
|
<resheader name="reader">System.Resources.ResXResourceReader, System.Windows.Forms, ...</resheader>
|
||||||
|
<resheader name="writer">System.Resources.ResXResourceWriter, System.Windows.Forms, ...</resheader>
|
||||||
|
<data name="Name1"><value>this is my long string</value><comment>this is a comment</comment></data>
|
||||||
|
<data name="Color1" type="System.Drawing.Color, System.Drawing">Blue</data>
|
||||||
|
<data name="Bitmap1" mimetype="application/x-microsoft.net.object.binary.base64">
|
||||||
|
<value>[base64 mime encoded serialized .NET Framework object]</value>
|
||||||
|
</data>
|
||||||
|
<data name="Icon1" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
|
||||||
|
<value>[base64 mime encoded string representing a byte array form of the .NET Framework object]</value>
|
||||||
|
<comment>This is a comment</comment>
|
||||||
|
</data>
|
||||||
|
|
||||||
|
There are any number of "resheader" rows that contain simple
|
||||||
|
name/value pairs.
|
||||||
|
|
||||||
|
Each data row contains a name, and value. The row also contains a
|
||||||
|
type or mimetype. Type corresponds to a .NET class that support
|
||||||
|
text/value conversion through the TypeConverter architecture.
|
||||||
|
Classes that don't support this are serialized and stored with the
|
||||||
|
mimetype set.
|
||||||
|
|
||||||
|
The mimetype is used for serialized objects, and tells the
|
||||||
|
ResXResourceReader how to depersist the object. This is currently not
|
||||||
|
extensible. For a given mimetype the value must be set accordingly:
|
||||||
|
|
||||||
|
Note - application/x-microsoft.net.object.binary.base64 is the format
|
||||||
|
that the ResXResourceWriter will generate, however the reader can
|
||||||
|
read any of the formats listed below.
|
||||||
|
|
||||||
|
mimetype: application/x-microsoft.net.object.binary.base64
|
||||||
|
value : The object must be serialized with
|
||||||
|
: System.Runtime.Serialization.Formatters.Binary.BinaryFormatter
|
||||||
|
: and then encoded with base64 encoding.
|
||||||
|
|
||||||
|
mimetype: application/x-microsoft.net.object.soap.base64
|
||||||
|
value : The object must be serialized with
|
||||||
|
: System.Runtime.Serialization.Formatters.Soap.SoapFormatter
|
||||||
|
: and then encoded with base64 encoding.
|
||||||
|
|
||||||
|
mimetype: application/x-microsoft.net.object.bytearray.base64
|
||||||
|
value : The object must be serialized into a byte array
|
||||||
|
: using a System.ComponentModel.TypeConverter
|
||||||
|
: and then encoded with base64 encoding.
|
||||||
|
-->
|
||||||
|
<xsd:schema id="root" xmlns="" xmlns:xsd="http://www.w3.org/2001/XMLSchema" xmlns:msdata="urn:schemas-microsoft-com:xml-msdata">
|
||||||
|
<xsd:import namespace="http://www.w3.org/XML/1998/namespace" />
|
||||||
|
<xsd:element name="root" msdata:IsDataSet="true">
|
||||||
|
<xsd:complexType>
|
||||||
|
<xsd:choice maxOccurs="unbounded">
|
||||||
|
<xsd:element name="metadata">
|
||||||
|
<xsd:complexType>
|
||||||
|
<xsd:sequence>
|
||||||
|
<xsd:element name="value" type="xsd:string" minOccurs="0" />
|
||||||
|
</xsd:sequence>
|
||||||
|
<xsd:attribute name="name" use="required" type="xsd:string" />
|
||||||
|
<xsd:attribute name="type" type="xsd:string" />
|
||||||
|
<xsd:attribute name="mimetype" type="xsd:string" />
|
||||||
|
<xsd:attribute ref="xml:space" />
|
||||||
|
</xsd:complexType>
|
||||||
|
</xsd:element>
|
||||||
|
<xsd:element name="assembly">
|
||||||
|
<xsd:complexType>
|
||||||
|
<xsd:attribute name="alias" type="xsd:string" />
|
||||||
|
<xsd:attribute name="name" type="xsd:string" />
|
||||||
|
</xsd:complexType>
|
||||||
|
</xsd:element>
|
||||||
|
<xsd:element name="data">
|
||||||
|
<xsd:complexType>
|
||||||
|
<xsd:sequence>
|
||||||
|
<xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
|
||||||
|
<xsd:element name="comment" type="xsd:string" minOccurs="0" msdata:Ordinal="2" />
|
||||||
|
</xsd:sequence>
|
||||||
|
<xsd:attribute name="name" type="xsd:string" use="required" msdata:Ordinal="1" />
|
||||||
|
<xsd:attribute name="type" type="xsd:string" msdata:Ordinal="3" />
|
||||||
|
<xsd:attribute name="mimetype" type="xsd:string" msdata:Ordinal="4" />
|
||||||
|
<xsd:attribute ref="xml:space" />
|
||||||
|
</xsd:complexType>
|
||||||
|
</xsd:element>
|
||||||
|
<xsd:element name="resheader">
|
||||||
|
<xsd:complexType>
|
||||||
|
<xsd:sequence>
|
||||||
|
<xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
|
||||||
|
</xsd:sequence>
|
||||||
|
<xsd:attribute name="name" type="xsd:string" use="required" />
|
||||||
|
</xsd:complexType>
|
||||||
|
</xsd:element>
|
||||||
|
</xsd:choice>
|
||||||
|
</xsd:complexType>
|
||||||
|
</xsd:element>
|
||||||
|
</xsd:schema>
|
||||||
|
<resheader name="resmimetype">
|
||||||
|
<value>text/microsoft-resx</value>
|
||||||
|
</resheader>
|
||||||
|
<resheader name="version">
|
||||||
|
<value>2.0</value>
|
||||||
|
</resheader>
|
||||||
|
<resheader name="reader">
|
||||||
|
<value>System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||||
|
</resheader>
|
||||||
|
<resheader name="writer">
|
||||||
|
<value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||||
|
</resheader>
|
||||||
|
<metadata name="GpsStatusBindingSource.TrayLocation" type="System.Drawing.Point, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a">
|
||||||
|
<value>17, 17</value>
|
||||||
|
</metadata>
|
||||||
|
</root>
|
@ -34,10 +34,10 @@ namespace ArducopterConfigurator
|
|||||||
this.txtSend = new System.Windows.Forms.TextBox();
|
this.txtSend = new System.Windows.Forms.TextBox();
|
||||||
this.button1 = new System.Windows.Forms.Button();
|
this.button1 = new System.Windows.Forms.Button();
|
||||||
this.groupBox1 = new System.Windows.Forms.GroupBox();
|
this.groupBox1 = new System.Windows.Forms.GroupBox();
|
||||||
|
this.positionHoldConfigView1 = new ArducopterConfigurator.Views.PositionHoldConfigView();
|
||||||
this.groupBox2 = new System.Windows.Forms.GroupBox();
|
this.groupBox2 = new System.Windows.Forms.GroupBox();
|
||||||
this.altitudeHoldConfigView1 = new ArducopterConfigurator.Views.AltitudeHoldConfigView();
|
this.altitudeHoldConfigView1 = new ArducopterConfigurator.Views.AltitudeHoldConfigView();
|
||||||
this.PositionAltitudePidsBindingSource = new System.Windows.Forms.BindingSource(this.components);
|
this.PositionAltitudePidsBindingSource = new System.Windows.Forms.BindingSource(this.components);
|
||||||
this.positionHoldConfigView1 = new ArducopterConfigurator.Views.PositionHoldConfigView();
|
|
||||||
this.groupBox1.SuspendLayout();
|
this.groupBox1.SuspendLayout();
|
||||||
this.groupBox2.SuspendLayout();
|
this.groupBox2.SuspendLayout();
|
||||||
((System.ComponentModel.ISupportInitialize)(this.PositionAltitudePidsBindingSource)).BeginInit();
|
((System.ComponentModel.ISupportInitialize)(this.PositionAltitudePidsBindingSource)).BeginInit();
|
||||||
@ -53,7 +53,7 @@ namespace ArducopterConfigurator
|
|||||||
// button1
|
// button1
|
||||||
//
|
//
|
||||||
this.button1.Anchor = ((System.Windows.Forms.AnchorStyles)((System.Windows.Forms.AnchorStyles.Bottom | System.Windows.Forms.AnchorStyles.Right)));
|
this.button1.Anchor = ((System.Windows.Forms.AnchorStyles)((System.Windows.Forms.AnchorStyles.Bottom | System.Windows.Forms.AnchorStyles.Right)));
|
||||||
this.button1.Location = new System.Drawing.Point(980, 929);
|
this.button1.Location = new System.Drawing.Point(1264, 929);
|
||||||
this.button1.Name = "button1";
|
this.button1.Name = "button1";
|
||||||
this.button1.Size = new System.Drawing.Size(104, 23);
|
this.button1.Size = new System.Drawing.Size(104, 23);
|
||||||
this.button1.TabIndex = 6;
|
this.button1.TabIndex = 6;
|
||||||
@ -70,12 +70,19 @@ namespace ArducopterConfigurator
|
|||||||
this.groupBox1.TabStop = false;
|
this.groupBox1.TabStop = false;
|
||||||
this.groupBox1.Text = "Position Hold";
|
this.groupBox1.Text = "Position Hold";
|
||||||
//
|
//
|
||||||
|
// positionHoldConfigView1
|
||||||
|
//
|
||||||
|
this.positionHoldConfigView1.Location = new System.Drawing.Point(7, 20);
|
||||||
|
this.positionHoldConfigView1.Name = "positionHoldConfigView1";
|
||||||
|
this.positionHoldConfigView1.Size = new System.Drawing.Size(259, 139);
|
||||||
|
this.positionHoldConfigView1.TabIndex = 0;
|
||||||
|
//
|
||||||
// groupBox2
|
// groupBox2
|
||||||
//
|
//
|
||||||
this.groupBox2.Controls.Add(this.altitudeHoldConfigView1);
|
this.groupBox2.Controls.Add(this.altitudeHoldConfigView1);
|
||||||
this.groupBox2.Location = new System.Drawing.Point(7, 177);
|
this.groupBox2.Location = new System.Drawing.Point(7, 177);
|
||||||
this.groupBox2.Name = "groupBox2";
|
this.groupBox2.Name = "groupBox2";
|
||||||
this.groupBox2.Size = new System.Drawing.Size(283, 167);
|
this.groupBox2.Size = new System.Drawing.Size(283, 112);
|
||||||
this.groupBox2.TabIndex = 10;
|
this.groupBox2.TabIndex = 10;
|
||||||
this.groupBox2.TabStop = false;
|
this.groupBox2.TabStop = false;
|
||||||
this.groupBox2.Text = "Altitude Hold";
|
this.groupBox2.Text = "Altitude Hold";
|
||||||
@ -84,20 +91,13 @@ namespace ArducopterConfigurator
|
|||||||
//
|
//
|
||||||
this.altitudeHoldConfigView1.Location = new System.Drawing.Point(7, 20);
|
this.altitudeHoldConfigView1.Location = new System.Drawing.Point(7, 20);
|
||||||
this.altitudeHoldConfigView1.Name = "altitudeHoldConfigView1";
|
this.altitudeHoldConfigView1.Name = "altitudeHoldConfigView1";
|
||||||
this.altitudeHoldConfigView1.Size = new System.Drawing.Size(276, 122);
|
this.altitudeHoldConfigView1.Size = new System.Drawing.Size(270, 91);
|
||||||
this.altitudeHoldConfigView1.TabIndex = 0;
|
this.altitudeHoldConfigView1.TabIndex = 0;
|
||||||
//
|
//
|
||||||
// PositionAltitudePidsBindingSource
|
// PositionAltitudePidsBindingSource
|
||||||
//
|
//
|
||||||
this.PositionAltitudePidsBindingSource.DataSource = typeof(ArducopterConfigurator.PresentationModels.FlightControlPidsVm);
|
this.PositionAltitudePidsBindingSource.DataSource = typeof(ArducopterConfigurator.PresentationModels.FlightControlPidsVm);
|
||||||
//
|
//
|
||||||
// positionHoldConfigView1
|
|
||||||
//
|
|
||||||
this.positionHoldConfigView1.Location = new System.Drawing.Point(7, 20);
|
|
||||||
this.positionHoldConfigView1.Name = "positionHoldConfigView1";
|
|
||||||
this.positionHoldConfigView1.Size = new System.Drawing.Size(259, 139);
|
|
||||||
this.positionHoldConfigView1.TabIndex = 0;
|
|
||||||
//
|
|
||||||
// PositionAltitudePidsView
|
// PositionAltitudePidsView
|
||||||
//
|
//
|
||||||
this.AutoScaleDimensions = new System.Drawing.SizeF(6F, 13F);
|
this.AutoScaleDimensions = new System.Drawing.SizeF(6F, 13F);
|
||||||
@ -109,7 +109,7 @@ namespace ArducopterConfigurator
|
|||||||
this.Controls.Add(this.button1);
|
this.Controls.Add(this.button1);
|
||||||
this.Controls.Add(this.txtSend);
|
this.Controls.Add(this.txtSend);
|
||||||
this.Name = "PositionAltitudePidsView";
|
this.Name = "PositionAltitudePidsView";
|
||||||
this.Size = new System.Drawing.Size(400, 476);
|
this.Size = new System.Drawing.Size(684, 476);
|
||||||
this.groupBox1.ResumeLayout(false);
|
this.groupBox1.ResumeLayout(false);
|
||||||
this.groupBox2.ResumeLayout(false);
|
this.groupBox2.ResumeLayout(false);
|
||||||
((System.ComponentModel.ISupportInitialize)(this.PositionAltitudePidsBindingSource)).EndInit();
|
((System.ComponentModel.ISupportInitialize)(this.PositionAltitudePidsBindingSource)).EndInit();
|
||||||
|
@ -117,7 +117,7 @@
|
|||||||
<resheader name="writer">
|
<resheader name="writer">
|
||||||
<value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
<value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||||
</resheader>
|
</resheader>
|
||||||
<metadata name="FlightControlPidsBindingSource.TrayLocation" type="System.Drawing.Point, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a">
|
<metadata name="PositionAltitudePidsBindingSource.TrayLocation" type="System.Drawing.Point, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a">
|
||||||
<value>17, 17</value>
|
<value>17, 17</value>
|
||||||
</metadata>
|
</metadata>
|
||||||
</root>
|
</root>
|
@ -32,6 +32,7 @@ namespace ArducopterConfigurator
|
|||||||
{typeof (SerialMonitorVm), typeof (SerialMonitorView)},
|
{typeof (SerialMonitorVm), typeof (SerialMonitorView)},
|
||||||
{typeof (FlightControlPidsVm), typeof (FlightControlPidsView)},
|
{typeof (FlightControlPidsVm), typeof (FlightControlPidsView)},
|
||||||
{typeof (PositionAltitudePidsVm), typeof (PositionAltitudePidsView)},
|
{typeof (PositionAltitudePidsVm), typeof (PositionAltitudePidsView)},
|
||||||
|
{typeof (GpsStatusVm), typeof (GpsStatusView)},
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user