Configurator.Net: Added heading field

git-svn-id: https://arducopter.googlecode.com/svn/trunk@1730 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
mandrolic 2011-02-27 08:09:16 +00:00
parent 5758d3dcf0
commit 86e4cd4fee
6 changed files with 67 additions and 7 deletions

View File

@ -33,7 +33,7 @@
<CreateWebPageOnPublish>true</CreateWebPageOnPublish>
<WebPage>index.htm</WebPage>
<OpenBrowserOnPublish>false</OpenBrowserOnPublish>
<ApplicationRevision>6</ApplicationRevision>
<ApplicationRevision>7</ApplicationRevision>
<ApplicationVersion>1.0.0.%2a</ApplicationVersion>
<UseApplicationTrust>false</UseApplicationTrust>
<PublishWizardCompleted>true</PublishWizardCompleted>

View File

@ -61,6 +61,7 @@ namespace ArducopterConfigurator
catch (Exception ex)
{
Error = ex.Message;
return false;
}
return true;
}

View File

@ -182,7 +182,12 @@ namespace ArducopterConfigurator.PresentationModels
_comms.CommPort = SelectedPort;
// Todo: check the status of this call success/failure
_comms.Connect();
if (!_comms.Connect())
{
ConnectionState = SessionStates.Disconnected;
ApmVersion = "Error";
return;
}
ConnectionState = SessionStates.Connecting;

View File

@ -95,7 +95,7 @@ namespace ArducopterConfigurator.PresentationModels
"AccelRoll",
"AccelPitch",
"AccelZ",
"UnusedFloat", // AP_Compass.heading
"CompassHeading", // AP_Compass.heading
"UnusedFloat", // AP_Compass.heading_x
"UnusedFloat", // AP_Compass.heading_y
"Unused", // AP_Compass.mag_x
@ -368,6 +368,36 @@ namespace ArducopterConfigurator.PresentationModels
}
}
private float _compassHeading;
/// <summary>
/// The current compass Heading as read from the magnetometer in radians?
/// </summary>
public float CompassHeading
{
get { return _compassHeading; }
set
{
if (_compassHeading == value) return;
_compassHeading = value;
FirePropertyChanged("CompassHeading");
FirePropertyChanged("CompassHeadingDegrees");
}
}
/// <summary>
/// The current compass Heading as read from the magnetometer in degrees
/// </summary>
public float CompassHeadingDegrees
{
get
{
var degrees = (float) ((CompassHeading) * (180 / Math.PI));
return (360 + degrees) % 360;
}
}
#endregion
public int Unused { get; set; }

View File

@ -71,6 +71,8 @@
this.cirularIndicatorControl5 = new ArducopterConfigurator.Views.controls.CirularIndicatorControl();
this.toolTip1 = new System.Windows.Forms.ToolTip(this.components);
this.label1 = new System.Windows.Forms.Label();
this.textBox14 = new System.Windows.Forms.TextBox();
this.label2 = new System.Windows.Forms.Label();
((System.ComponentModel.ISupportInitialize)(this.FlightDataVmBindingSource)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.pictureBox1)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.pictureBox2)).BeginInit();
@ -608,10 +610,33 @@
this.label1.TabIndex = 57;
this.label1.Text = "ARMED";
//
// textBox14
//
this.textBox14.BorderStyle = System.Windows.Forms.BorderStyle.FixedSingle;
this.textBox14.DataBindings.Add(new System.Windows.Forms.Binding("Text", this.FlightDataVmBindingSource, "CompassHeadingDegrees", true, System.Windows.Forms.DataSourceUpdateMode.OnValidation, null, "N0"));
this.textBox14.Enabled = false;
this.textBox14.Location = new System.Drawing.Point(102, 244);
this.textBox14.Name = "textBox14";
this.textBox14.ReadOnly = true;
this.textBox14.Size = new System.Drawing.Size(35, 20);
this.textBox14.TabIndex = 58;
this.textBox14.TextAlign = System.Windows.Forms.HorizontalAlignment.Center;
//
// label2
//
this.label2.AutoSize = true;
this.label2.Location = new System.Drawing.Point(44, 246);
this.label2.Name = "label2";
this.label2.Size = new System.Drawing.Size(47, 13);
this.label2.TabIndex = 59;
this.label2.Text = "Heading";
//
// FlightDataView
//
this.AutoScaleDimensions = new System.Drawing.SizeF(6F, 13F);
this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font;
this.Controls.Add(this.label2);
this.Controls.Add(this.textBox14);
this.Controls.Add(this.label1);
this.Controls.Add(this.cirularIndicatorControl5);
this.Controls.Add(this.cirularIndicatorControl4);
@ -652,7 +677,7 @@
this.Controls.Add(this.pictureBox2);
this.DoubleBuffered = true;
this.Name = "FlightDataView";
this.Size = new System.Drawing.Size(453, 260);
this.Size = new System.Drawing.Size(453, 273);
((System.ComponentModel.ISupportInitialize)(this.FlightDataVmBindingSource)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.pictureBox1)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.pictureBox2)).EndInit();
@ -704,5 +729,7 @@
private ArducopterConfigurator.Views.controls.CirularIndicatorControl cirularIndicatorControl5;
private System.Windows.Forms.ToolTip toolTip1;
private System.Windows.Forms.Label label1;
private System.Windows.Forms.TextBox textBox14;
private System.Windows.Forms.Label label2;
}
}

View File

@ -172,7 +172,4 @@
kDAHyJw4EoECAARSrmTK0SPIjAQxYjW4taBWrF8zhrU4tkBAADs=
</value>
</data>
<metadata name="toolTip1.TrayLocation" type="System.Drawing.Point, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a">
<value>225, 28</value>
</metadata>
</root>