mirror of https://github.com/ArduPilot/ardupilot
Configurator.Net: Added High/Low watermarks to transmitter controls for calibration
git-svn-id: https://arducopter.googlecode.com/svn/trunk@1590 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
d5e48364a1
commit
ff487bda00
|
@ -13,7 +13,7 @@ namespace ArducopterConfigurator
|
|||
/// </remarks>
|
||||
public abstract class MonitorVm : NotifyProperyChangedBase, IPresentationModel
|
||||
{
|
||||
private IComms _sp;
|
||||
private readonly IComms _sp;
|
||||
protected bool isActive;
|
||||
protected string[] PropsInUpdateOrder;
|
||||
|
||||
|
@ -92,7 +92,7 @@ namespace ArducopterConfigurator
|
|||
|
||||
if (PropsInUpdateOrder.Length!=strs.Length)
|
||||
{
|
||||
Console.WriteLine("Processing update with only " + strs.Length
|
||||
Console.WriteLine("Processing update with " + strs.Length
|
||||
+ " values, but have " + PropsInUpdateOrder.Length
|
||||
+ " properties to populate. Ignoring this update");
|
||||
return;
|
||||
|
@ -104,6 +104,12 @@ namespace ArducopterConfigurator
|
|||
var s = strs[i];
|
||||
object value = null;
|
||||
|
||||
if (prop == null)
|
||||
{
|
||||
Console.WriteLine("Trying to set non existant property: " + PropsInUpdateOrder[i]);
|
||||
break;
|
||||
}
|
||||
|
||||
if (prop.PropertyType == typeof(float))
|
||||
{
|
||||
float val;
|
||||
|
|
|
@ -19,8 +19,22 @@ namespace ArducopterConfigurator.PresentationModels
|
|||
"PitchMidValue",
|
||||
"YawMidValue",
|
||||
};
|
||||
|
||||
ResetCommand = new DelegateCommand(_ => ResetWatermarks());
|
||||
}
|
||||
|
||||
private void ResetWatermarks()
|
||||
{
|
||||
ThrottleMin = ThrottleMax = Throttle;
|
||||
RollMax = RollMin = Roll;
|
||||
YawMax = YawMin = Yaw;
|
||||
PitchMax = PitchMin = Pitch;
|
||||
AuxMax = AuxMin = Aux;
|
||||
ModeMax = ModeMin = Mode;
|
||||
}
|
||||
|
||||
|
||||
public ICommand ResetCommand { get; private set; }
|
||||
|
||||
private int _roll;
|
||||
public int Roll
|
||||
|
@ -31,6 +45,34 @@ namespace ArducopterConfigurator.PresentationModels
|
|||
if (_roll == value) return;
|
||||
_roll = value;
|
||||
FirePropertyChanged("Roll");
|
||||
if (value > RollMax)
|
||||
RollMax = value;
|
||||
if (value < RollMin)
|
||||
RollMin = value;
|
||||
}
|
||||
}
|
||||
|
||||
private int _rollMax;
|
||||
public int RollMax
|
||||
{
|
||||
get { return _rollMax; }
|
||||
set
|
||||
{
|
||||
if (_rollMax == value) return;
|
||||
_rollMax = value;
|
||||
FirePropertyChanged("RollMax");
|
||||
}
|
||||
}
|
||||
|
||||
private int _rollMin;
|
||||
public int RollMin
|
||||
{
|
||||
get { return _rollMin; }
|
||||
set
|
||||
{
|
||||
if (_rollMin == value) return;
|
||||
_rollMin = value;
|
||||
FirePropertyChanged("RollMin");
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -43,9 +85,39 @@ namespace ArducopterConfigurator.PresentationModels
|
|||
if (_pitch == value) return;
|
||||
_pitch = value;
|
||||
FirePropertyChanged("Pitch");
|
||||
if (value > PitchMax)
|
||||
PitchMax = value;
|
||||
if (value < PitchMin)
|
||||
PitchMin = value;
|
||||
}
|
||||
}
|
||||
|
||||
private int _pitchMax;
|
||||
public int PitchMax
|
||||
{
|
||||
get { return _pitchMax; }
|
||||
set
|
||||
{
|
||||
if (_pitchMax == value) return;
|
||||
_pitchMax = value;
|
||||
FirePropertyChanged("PitchMax");
|
||||
}
|
||||
}
|
||||
|
||||
private int _pitchMin;
|
||||
|
||||
public int PitchMin
|
||||
{
|
||||
get { return _pitchMin; }
|
||||
set
|
||||
{
|
||||
if (_pitchMin == value) return;
|
||||
_pitchMin = value;
|
||||
FirePropertyChanged("PitchMin");
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
private int _yaw;
|
||||
public int Yaw
|
||||
{
|
||||
|
@ -55,6 +127,34 @@ namespace ArducopterConfigurator.PresentationModels
|
|||
if (_yaw == value) return;
|
||||
_yaw = value;
|
||||
FirePropertyChanged("Yaw");
|
||||
if (value > YawMax)
|
||||
YawMax = value;
|
||||
if (value < YawMin)
|
||||
YawMin = value;
|
||||
}
|
||||
}
|
||||
|
||||
private int _yawMax;
|
||||
public int YawMax
|
||||
{
|
||||
get { return _yawMax; }
|
||||
set
|
||||
{
|
||||
if (_yawMax == value) return;
|
||||
_yawMax = value;
|
||||
FirePropertyChanged("YawMax");
|
||||
}
|
||||
}
|
||||
|
||||
private int _yawMin;
|
||||
public int YawMin
|
||||
{
|
||||
get { return _yawMin; }
|
||||
set
|
||||
{
|
||||
if (_yawMin == value) return;
|
||||
_yawMin = value;
|
||||
FirePropertyChanged("YawMin");
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -67,9 +167,39 @@ namespace ArducopterConfigurator.PresentationModels
|
|||
if (_throttle == value) return;
|
||||
_throttle = value;
|
||||
FirePropertyChanged("Throttle");
|
||||
if (value > ThrottleMax)
|
||||
ThrottleMax = value;
|
||||
if (value < ThrottleMin)
|
||||
ThrottleMin = value;
|
||||
}
|
||||
}
|
||||
|
||||
private int _throttleMin;
|
||||
public int ThrottleMin
|
||||
{
|
||||
get { return _throttleMin; }
|
||||
set
|
||||
{
|
||||
if (_throttleMin == value) return;
|
||||
_throttleMin = value;
|
||||
FirePropertyChanged("ThrottleMin");
|
||||
}
|
||||
}
|
||||
|
||||
private int _throttleMax;
|
||||
public int ThrottleMax
|
||||
{
|
||||
get { return _throttleMax; }
|
||||
set
|
||||
{
|
||||
if (_throttleMax == value) return;
|
||||
_throttleMax = value;
|
||||
FirePropertyChanged("ThrottleMax");
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
private int _mode;
|
||||
public int Mode
|
||||
|
@ -80,6 +210,34 @@ namespace ArducopterConfigurator.PresentationModels
|
|||
if (_mode == value) return;
|
||||
_mode = value;
|
||||
FirePropertyChanged("Mode");
|
||||
if (value > ModeMax)
|
||||
ModeMax = value;
|
||||
if (value < ModeMin)
|
||||
ModeMin = value;
|
||||
}
|
||||
}
|
||||
|
||||
private int _modeMax;
|
||||
public int ModeMax
|
||||
{
|
||||
get { return _modeMax; }
|
||||
set
|
||||
{
|
||||
if (_modeMax == value) return;
|
||||
_modeMax = value;
|
||||
FirePropertyChanged("ModeMax");
|
||||
}
|
||||
}
|
||||
|
||||
private int _modeMin;
|
||||
public int ModeMin
|
||||
{
|
||||
get { return _modeMin; }
|
||||
set
|
||||
{
|
||||
if (_modeMin == value) return;
|
||||
_modeMin = value;
|
||||
FirePropertyChanged("ModeMin");
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -92,48 +250,37 @@ namespace ArducopterConfigurator.PresentationModels
|
|||
if (_aux == value) return;
|
||||
_aux = value;
|
||||
FirePropertyChanged("Aux");
|
||||
if (value > AuxMax)
|
||||
AuxMax = value;
|
||||
if (value < AuxMin)
|
||||
AuxMin = value;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
private int _rollmid;
|
||||
public int RollMidValue
|
||||
private int _auxMax;
|
||||
public int AuxMax
|
||||
{
|
||||
get { return _rollmid; }
|
||||
get { return _auxMax; }
|
||||
set
|
||||
{
|
||||
if (_rollmid == value) return;
|
||||
_rollmid = value;
|
||||
FirePropertyChanged("RollMidValue");
|
||||
if (_auxMax == value) return;
|
||||
_auxMax = value;
|
||||
FirePropertyChanged("AuxMax");
|
||||
}
|
||||
}
|
||||
|
||||
private int _pitchMid;
|
||||
public int PitchMidValue
|
||||
private int _auxMin;
|
||||
public int AuxMin
|
||||
{
|
||||
get { return _pitchMid; }
|
||||
get { return _auxMin; }
|
||||
set
|
||||
{
|
||||
if (_pitchMid == value) return;
|
||||
_pitchMid = value;
|
||||
FirePropertyChanged("PitchMidValue");
|
||||
if (_auxMin == value) return;
|
||||
_auxMin = value;
|
||||
FirePropertyChanged("AuxMin");
|
||||
}
|
||||
}
|
||||
|
||||
private int _yawMid;
|
||||
public int YawMidValue
|
||||
{
|
||||
get { return _yawMid; }
|
||||
set
|
||||
{
|
||||
if (_yawMid == value) return;
|
||||
_yawMid = value;
|
||||
FirePropertyChanged("YawMidValue");
|
||||
}
|
||||
}
|
||||
|
||||
protected override void OnActivated()
|
||||
{
|
||||
|
|
|
@ -14,6 +14,7 @@ namespace ArducopterConfiguratorTest
|
|||
setCommand = "O";
|
||||
|
||||
_mockComms = new MockComms();
|
||||
_mockComms.Connect();
|
||||
_vm = new AcroModeConfigVm(_mockComms);
|
||||
}
|
||||
|
||||
|
|
|
@ -15,6 +15,7 @@ namespace ArducopterConfiguratorTest
|
|||
setCommand = "E";
|
||||
|
||||
_mockComms = new MockComms();
|
||||
_mockComms.Connect();
|
||||
_vm = new AltitudeHoldConfigVm(_mockComms);
|
||||
}
|
||||
|
||||
|
|
|
@ -1,4 +1,4 @@
|
|||
<?xml version="1.0" encoding="utf-8"?>
|
||||
<?xml version="1.0" encoding="utf-8"?>
|
||||
<Project ToolsVersion="3.5" DefaultTargets="Build" xmlns="http://schemas.microsoft.com/developer/msbuild/2003">
|
||||
<PropertyGroup>
|
||||
<Configuration Condition=" '$(Configuration)' == '' ">Debug</Configuration>
|
||||
|
@ -44,10 +44,12 @@
|
|||
<Compile Include="AltitudeHoldVmTest.cs" />
|
||||
<Compile Include="CalibrationOffsetsDataVmTest.cs" />
|
||||
<Compile Include="MainVmTests.cs" />
|
||||
<Compile Include="MockComms.cs" />
|
||||
<Compile Include="MotorCommandsVmTest.cs" />
|
||||
<Compile Include="PositionHoldConfigVmTest.cs" />
|
||||
<Compile Include="Properties\AssemblyInfo.cs" />
|
||||
<Compile Include="StableModeConfigVmTest.cs" />
|
||||
<Compile Include="TransmitterChannelsVmTests.cs" />
|
||||
<Compile Include="VmTestBase.cs" />
|
||||
</ItemGroup>
|
||||
<ItemGroup>
|
||||
|
|
|
@ -15,6 +15,7 @@ namespace ArducopterConfiguratorTest
|
|||
setCommand = "I";
|
||||
|
||||
_mockComms = new MockComms();
|
||||
_mockComms.Connect();
|
||||
_vm = new CalibrationOffsetsDataVm(_mockComms);
|
||||
}
|
||||
|
||||
|
|
|
@ -1,53 +1,9 @@
|
|||
using System;
|
||||
using System.Collections.Generic;
|
||||
using System.Text;
|
||||
using ArducopterConfigurator;
|
||||
using System.Text;
|
||||
using ArducopterConfigurator.PresentationModels;
|
||||
using NUnit.Framework;
|
||||
|
||||
namespace ArducopterConfiguratorTest
|
||||
{
|
||||
public class MockComms : IComms
|
||||
{
|
||||
public event Action<string> LineOfDataReceived;
|
||||
public string CommPort { get; set; }
|
||||
public List<string> SentItems = new List<string>();
|
||||
private bool _isConnected;
|
||||
|
||||
public bool IsConnected
|
||||
{
|
||||
get { return _isConnected; }
|
||||
}
|
||||
|
||||
public IEnumerable<string> ListCommPorts()
|
||||
{
|
||||
throw new NotImplementedException();
|
||||
}
|
||||
|
||||
public void Send(string send)
|
||||
{
|
||||
SentItems.Add(send);
|
||||
}
|
||||
|
||||
public bool Connect()
|
||||
{
|
||||
_isConnected = true;
|
||||
return true;
|
||||
}
|
||||
|
||||
public bool DisConnect()
|
||||
{
|
||||
_isConnected = false;
|
||||
return true;
|
||||
}
|
||||
|
||||
public void FireLineRecieve(string s)
|
||||
{
|
||||
if (LineOfDataReceived != null)
|
||||
LineOfDataReceived(s);
|
||||
}
|
||||
}
|
||||
|
||||
[TestFixture]
|
||||
public class MainVmTests
|
||||
{
|
||||
|
|
|
@ -0,0 +1,47 @@
|
|||
using System;
|
||||
using System.Collections.Generic;
|
||||
using ArducopterConfigurator;
|
||||
|
||||
namespace ArducopterConfiguratorTest
|
||||
{
|
||||
public class MockComms : IComms
|
||||
{
|
||||
public event Action<string> LineOfDataReceived;
|
||||
public string CommPort { get; set; }
|
||||
public List<string> SentItems = new List<string>();
|
||||
private bool _isConnected;
|
||||
|
||||
public bool IsConnected
|
||||
{
|
||||
get { return _isConnected; }
|
||||
}
|
||||
|
||||
public IEnumerable<string> ListCommPorts()
|
||||
{
|
||||
return new[] {"MockComport1"};
|
||||
}
|
||||
|
||||
public void Send(string send)
|
||||
{
|
||||
SentItems.Add(send);
|
||||
}
|
||||
|
||||
public bool Connect()
|
||||
{
|
||||
_isConnected = true;
|
||||
return true;
|
||||
}
|
||||
|
||||
public bool DisConnect()
|
||||
{
|
||||
_isConnected = false;
|
||||
return true;
|
||||
}
|
||||
|
||||
public void FireLineRecieve(string s)
|
||||
{
|
||||
if (LineOfDataReceived != null)
|
||||
LineOfDataReceived(s);
|
||||
}
|
||||
}
|
||||
}
|
|
@ -15,6 +15,7 @@ namespace ArducopterConfiguratorTest
|
|||
setCommand = "C";
|
||||
|
||||
_mockComms = new MockComms();
|
||||
_mockComms.Connect();
|
||||
_vm = new PositionHoldConfigVm(_mockComms);
|
||||
}
|
||||
|
||||
|
|
|
@ -15,6 +15,7 @@ namespace ArducopterConfiguratorTest
|
|||
setCommand = "A";
|
||||
|
||||
_mockComms = new MockComms();
|
||||
_mockComms.Connect();
|
||||
_vm = new StableModeConfigVm(_mockComms);
|
||||
}
|
||||
|
||||
|
|
|
@ -0,0 +1,77 @@
|
|||
using ArducopterConfigurator.PresentationModels;
|
||||
using NUnit.Framework;
|
||||
|
||||
namespace ArducopterConfiguratorTest
|
||||
{
|
||||
[TestFixture]
|
||||
public class TransmitterChannelsVmTests
|
||||
{
|
||||
private MockComms _mockComms;
|
||||
private TransmitterChannelsVm _vm;
|
||||
|
||||
[SetUp]
|
||||
public void Setup()
|
||||
{
|
||||
_mockComms = new MockComms();
|
||||
_mockComms.Connect();
|
||||
_vm = new TransmitterChannelsVm(_mockComms);
|
||||
|
||||
}
|
||||
|
||||
[Test]
|
||||
public void SendsCorrectCommandOnActivate()
|
||||
{
|
||||
_vm.Activate();
|
||||
Assert.AreEqual(1,_mockComms.SentItems.Count);
|
||||
Assert.AreEqual("U",_mockComms.SentItems[0]);
|
||||
}
|
||||
|
||||
[Test]
|
||||
public void SendsCorrectCommandOnDeActivate()
|
||||
{
|
||||
_vm.Activate();
|
||||
_vm.DeActivate();
|
||||
|
||||
Assert.AreEqual(2, _mockComms.SentItems.Count);
|
||||
Assert.AreEqual("X", _mockComms.SentItems[1]);
|
||||
}
|
||||
|
||||
[Test]
|
||||
public void ValuesAreSet()
|
||||
{
|
||||
_vm.Activate();
|
||||
// What do the MID values do?
|
||||
//1403,1620,1523,1501,1900,1950,0,0,0
|
||||
// Aileron,Elevator,Yaw,Throttle,AUX1 (Mode),AUX2 ,Roll MID value,Pitch MID value,Yaw MID Value
|
||||
|
||||
var sampleData = "1403,1620,1523,1501,1900,1950,0,0,0";
|
||||
_mockComms.FireLineRecieve(sampleData);
|
||||
Assert.AreEqual(1403, _vm.Roll);
|
||||
Assert.AreEqual(1620, _vm.Pitch);
|
||||
Assert.AreEqual(1523, _vm.Yaw);
|
||||
Assert.AreEqual(1501, _vm.Throttle);
|
||||
Assert.AreEqual(1900, _vm.Mode);
|
||||
Assert.AreEqual(1950, _vm.Aux);
|
||||
}
|
||||
|
||||
|
||||
[Test]
|
||||
public void MaximumsAndMinimumsAreSet()
|
||||
{
|
||||
_vm.Activate();
|
||||
// What do the MID values do?
|
||||
//1403,1620,1523,1501,1900,1950,0,0,0
|
||||
// Aileron,Elevator,Yaw,Throttle,AUX1 (Mode),AUX2 ,Roll MID value,Pitch MID value,Yaw MID Value
|
||||
|
||||
var sampleData = "1403,1620,1523,1501,1900,1950,0,0,0";
|
||||
_mockComms.FireLineRecieve(sampleData);
|
||||
_vm.ResetCommand.Execute(null);
|
||||
_mockComms.FireLineRecieve(sampleData);
|
||||
|
||||
Assert.AreEqual(1403,_vm.Roll);
|
||||
Assert.AreEqual(1403,_vm.RollMin);
|
||||
Assert.AreEqual(1403,_vm.RollMax);
|
||||
}
|
||||
|
||||
}
|
||||
}
|
|
@ -48,6 +48,7 @@
|
|||
this.linearIndicatorControl4 = new ArducopterConfigurator.Views.controls.LinearIndicatorControl();
|
||||
this.linearIndicatorControl5 = new ArducopterConfigurator.Views.controls.LinearIndicatorControl();
|
||||
this.linearIndicatorControl6 = new ArducopterConfigurator.Views.controls.LinearIndicatorControl();
|
||||
this.button1 = new System.Windows.Forms.Button();
|
||||
((System.ComponentModel.ISupportInitialize)(this.TransmitterChannelsBindingSource)).BeginInit();
|
||||
this.SuspendLayout();
|
||||
//
|
||||
|
@ -171,6 +172,8 @@
|
|||
this.linearIndicatorControl3.BarDark = System.Drawing.Color.FromArgb(((int)(((byte)(40)))), ((int)(((byte)(68)))), ((int)(((byte)(202)))));
|
||||
this.linearIndicatorControl3.BarDividersCount = 20;
|
||||
this.linearIndicatorControl3.BarLight = System.Drawing.Color.FromArgb(((int)(((byte)(102)))), ((int)(((byte)(144)))), ((int)(((byte)(252)))));
|
||||
this.linearIndicatorControl3.DataBindings.Add(new System.Windows.Forms.Binding("MaxWaterMark", this.TransmitterChannelsBindingSource, "ThrottleMax", true, System.Windows.Forms.DataSourceUpdateMode.Never));
|
||||
this.linearIndicatorControl3.DataBindings.Add(new System.Windows.Forms.Binding("MinWatermark", this.TransmitterChannelsBindingSource, "ThrottleMin", true, System.Windows.Forms.DataSourceUpdateMode.Never));
|
||||
this.linearIndicatorControl3.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.TransmitterChannelsBindingSource, "Throttle", true, System.Windows.Forms.DataSourceUpdateMode.Never));
|
||||
this.linearIndicatorControl3.IsVertical = true;
|
||||
this.linearIndicatorControl3.Location = new System.Drawing.Point(16, 30);
|
||||
|
@ -193,6 +196,8 @@
|
|||
this.linearIndicatorControl1.BarDark = System.Drawing.Color.FromArgb(((int)(((byte)(40)))), ((int)(((byte)(68)))), ((int)(((byte)(202)))));
|
||||
this.linearIndicatorControl1.BarDividersCount = 20;
|
||||
this.linearIndicatorControl1.BarLight = System.Drawing.Color.FromArgb(((int)(((byte)(102)))), ((int)(((byte)(144)))), ((int)(((byte)(252)))));
|
||||
this.linearIndicatorControl1.DataBindings.Add(new System.Windows.Forms.Binding("MaxWaterMark", this.TransmitterChannelsBindingSource, "PitchMax", true, System.Windows.Forms.DataSourceUpdateMode.Never));
|
||||
this.linearIndicatorControl1.DataBindings.Add(new System.Windows.Forms.Binding("MinWatermark", this.TransmitterChannelsBindingSource, "PitchMin", true, System.Windows.Forms.DataSourceUpdateMode.Never));
|
||||
this.linearIndicatorControl1.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.TransmitterChannelsBindingSource, "Pitch", true));
|
||||
this.linearIndicatorControl1.IsVertical = true;
|
||||
this.linearIndicatorControl1.Location = new System.Drawing.Point(67, 30);
|
||||
|
@ -205,7 +210,7 @@
|
|||
this.linearIndicatorControl1.Size = new System.Drawing.Size(20, 111);
|
||||
this.linearIndicatorControl1.TabIndex = 44;
|
||||
this.linearIndicatorControl1.Value = 1100;
|
||||
this.linearIndicatorControl1.WatermarkLineColor = System.Drawing.Color.DarkGray;
|
||||
this.linearIndicatorControl1.WatermarkLineColor = System.Drawing.Color.Red;
|
||||
//
|
||||
// linearIndicatorControl2
|
||||
//
|
||||
|
@ -215,6 +220,8 @@
|
|||
this.linearIndicatorControl2.BarDark = System.Drawing.Color.FromArgb(((int)(((byte)(40)))), ((int)(((byte)(68)))), ((int)(((byte)(202)))));
|
||||
this.linearIndicatorControl2.BarDividersCount = 20;
|
||||
this.linearIndicatorControl2.BarLight = System.Drawing.Color.FromArgb(((int)(((byte)(102)))), ((int)(((byte)(144)))), ((int)(((byte)(252)))));
|
||||
this.linearIndicatorControl2.DataBindings.Add(new System.Windows.Forms.Binding("MaxWaterMark", this.TransmitterChannelsBindingSource, "ModeMax", true, System.Windows.Forms.DataSourceUpdateMode.Never));
|
||||
this.linearIndicatorControl2.DataBindings.Add(new System.Windows.Forms.Binding("MinWatermark", this.TransmitterChannelsBindingSource, "ModeMin", true, System.Windows.Forms.DataSourceUpdateMode.Never));
|
||||
this.linearIndicatorControl2.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.TransmitterChannelsBindingSource, "Mode", true));
|
||||
this.linearIndicatorControl2.IsVertical = true;
|
||||
this.linearIndicatorControl2.Location = new System.Drawing.Point(155, 131);
|
||||
|
@ -227,7 +234,7 @@
|
|||
this.linearIndicatorControl2.Size = new System.Drawing.Size(20, 73);
|
||||
this.linearIndicatorControl2.TabIndex = 45;
|
||||
this.linearIndicatorControl2.Value = 1050;
|
||||
this.linearIndicatorControl2.WatermarkLineColor = System.Drawing.Color.DarkGray;
|
||||
this.linearIndicatorControl2.WatermarkLineColor = System.Drawing.Color.Red;
|
||||
//
|
||||
// linearIndicatorControl4
|
||||
//
|
||||
|
@ -237,6 +244,8 @@
|
|||
this.linearIndicatorControl4.BarDark = System.Drawing.Color.FromArgb(((int)(((byte)(40)))), ((int)(((byte)(68)))), ((int)(((byte)(202)))));
|
||||
this.linearIndicatorControl4.BarDividersCount = 20;
|
||||
this.linearIndicatorControl4.BarLight = System.Drawing.Color.FromArgb(((int)(((byte)(102)))), ((int)(((byte)(144)))), ((int)(((byte)(252)))));
|
||||
this.linearIndicatorControl4.DataBindings.Add(new System.Windows.Forms.Binding("MaxWaterMark", this.TransmitterChannelsBindingSource, "AuxMax", true, System.Windows.Forms.DataSourceUpdateMode.Never));
|
||||
this.linearIndicatorControl4.DataBindings.Add(new System.Windows.Forms.Binding("MinWatermark", this.TransmitterChannelsBindingSource, "AuxMin", true, System.Windows.Forms.DataSourceUpdateMode.Never));
|
||||
this.linearIndicatorControl4.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.TransmitterChannelsBindingSource, "Aux", true));
|
||||
this.linearIndicatorControl4.IsVertical = true;
|
||||
this.linearIndicatorControl4.Location = new System.Drawing.Point(206, 131);
|
||||
|
@ -249,7 +258,7 @@
|
|||
this.linearIndicatorControl4.Size = new System.Drawing.Size(20, 73);
|
||||
this.linearIndicatorControl4.TabIndex = 46;
|
||||
this.linearIndicatorControl4.Value = 1900;
|
||||
this.linearIndicatorControl4.WatermarkLineColor = System.Drawing.Color.DarkGray;
|
||||
this.linearIndicatorControl4.WatermarkLineColor = System.Drawing.Color.Red;
|
||||
//
|
||||
// linearIndicatorControl5
|
||||
//
|
||||
|
@ -259,6 +268,8 @@
|
|||
this.linearIndicatorControl5.BarDark = System.Drawing.Color.FromArgb(((int)(((byte)(40)))), ((int)(((byte)(68)))), ((int)(((byte)(202)))));
|
||||
this.linearIndicatorControl5.BarDividersCount = 20;
|
||||
this.linearIndicatorControl5.BarLight = System.Drawing.Color.FromArgb(((int)(((byte)(102)))), ((int)(((byte)(144)))), ((int)(((byte)(252)))));
|
||||
this.linearIndicatorControl5.DataBindings.Add(new System.Windows.Forms.Binding("MaxWaterMark", this.TransmitterChannelsBindingSource, "RollMax", true, System.Windows.Forms.DataSourceUpdateMode.Never));
|
||||
this.linearIndicatorControl5.DataBindings.Add(new System.Windows.Forms.Binding("MinWatermark", this.TransmitterChannelsBindingSource, "RollMin", true, System.Windows.Forms.DataSourceUpdateMode.Never));
|
||||
this.linearIndicatorControl5.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.TransmitterChannelsBindingSource, "Roll", true));
|
||||
this.linearIndicatorControl5.IsVertical = false;
|
||||
this.linearIndicatorControl5.Location = new System.Drawing.Point(174, 80);
|
||||
|
@ -271,7 +282,7 @@
|
|||
this.linearIndicatorControl5.Size = new System.Drawing.Size(100, 20);
|
||||
this.linearIndicatorControl5.TabIndex = 47;
|
||||
this.linearIndicatorControl5.Value = 1300;
|
||||
this.linearIndicatorControl5.WatermarkLineColor = System.Drawing.Color.DarkGray;
|
||||
this.linearIndicatorControl5.WatermarkLineColor = System.Drawing.Color.Red;
|
||||
//
|
||||
// linearIndicatorControl6
|
||||
//
|
||||
|
@ -281,6 +292,8 @@
|
|||
this.linearIndicatorControl6.BarDark = System.Drawing.Color.FromArgb(((int)(((byte)(40)))), ((int)(((byte)(68)))), ((int)(((byte)(202)))));
|
||||
this.linearIndicatorControl6.BarDividersCount = 20;
|
||||
this.linearIndicatorControl6.BarLight = System.Drawing.Color.FromArgb(((int)(((byte)(102)))), ((int)(((byte)(144)))), ((int)(((byte)(252)))));
|
||||
this.linearIndicatorControl6.DataBindings.Add(new System.Windows.Forms.Binding("MaxWaterMark", this.TransmitterChannelsBindingSource, "YawMax", true, System.Windows.Forms.DataSourceUpdateMode.Never));
|
||||
this.linearIndicatorControl6.DataBindings.Add(new System.Windows.Forms.Binding("MinWatermark", this.TransmitterChannelsBindingSource, "YawMin", true, System.Windows.Forms.DataSourceUpdateMode.Never));
|
||||
this.linearIndicatorControl6.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.TransmitterChannelsBindingSource, "Yaw", true));
|
||||
this.linearIndicatorControl6.IsVertical = false;
|
||||
this.linearIndicatorControl6.Location = new System.Drawing.Point(174, 30);
|
||||
|
@ -293,12 +306,23 @@
|
|||
this.linearIndicatorControl6.Size = new System.Drawing.Size(100, 20);
|
||||
this.linearIndicatorControl6.TabIndex = 48;
|
||||
this.linearIndicatorControl6.Value = 1200;
|
||||
this.linearIndicatorControl6.WatermarkLineColor = System.Drawing.Color.DarkGray;
|
||||
this.linearIndicatorControl6.WatermarkLineColor = System.Drawing.Color.Red;
|
||||
//
|
||||
// button1
|
||||
//
|
||||
this.button1.DataBindings.Add(new System.Windows.Forms.Binding("Tag", this.TransmitterChannelsBindingSource, "ResetCommand", true));
|
||||
this.button1.Location = new System.Drawing.Point(7, 174);
|
||||
this.button1.Name = "button1";
|
||||
this.button1.Size = new System.Drawing.Size(75, 23);
|
||||
this.button1.TabIndex = 49;
|
||||
this.button1.Text = "Reset";
|
||||
this.button1.UseVisualStyleBackColor = true;
|
||||
//
|
||||
// TransmitterChannelsView
|
||||
//
|
||||
this.AutoScaleDimensions = new System.Drawing.SizeF(6F, 13F);
|
||||
this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font;
|
||||
this.Controls.Add(this.button1);
|
||||
this.Controls.Add(this.linearIndicatorControl6);
|
||||
this.Controls.Add(this.linearIndicatorControl5);
|
||||
this.Controls.Add(this.linearIndicatorControl4);
|
||||
|
@ -346,5 +370,6 @@
|
|||
private ArducopterConfigurator.Views.controls.LinearIndicatorControl linearIndicatorControl4;
|
||||
private ArducopterConfigurator.Views.controls.LinearIndicatorControl linearIndicatorControl5;
|
||||
private ArducopterConfigurator.Views.controls.LinearIndicatorControl linearIndicatorControl6;
|
||||
private System.Windows.Forms.Button button1;
|
||||
}
|
||||
}
|
||||
|
|
|
@ -14,6 +14,7 @@ namespace ArducopterConfigurator.Views
|
|||
public TransmitterChannelsView()
|
||||
{
|
||||
InitializeComponent();
|
||||
BindButtons();
|
||||
}
|
||||
|
||||
public override void SetDataContext(TransmitterChannelsVm model)
|
||||
|
|
Loading…
Reference in New Issue