Browse Source
git-svn-id: https://arducopter.googlecode.com/svn/trunk@1226 f9c3cf11-9bcb-44bc-f272-b75c42450872mission-4.1.18
mandrolic
14 years ago
6 changed files with 183 additions and 96 deletions
@ -0,0 +1,86 @@ |
|||||||
|
using ArducopterConfigurator.PresentationModels; |
||||||
|
using NUnit.Framework; |
||||||
|
|
||||||
|
namespace ArducopterConfiguratorTest |
||||||
|
{ |
||||||
|
[TestFixture] |
||||||
|
public class AcroModeConfigVmTest : VmTestBase<AcroModeConfigVm> |
||||||
|
{ |
||||||
|
[SetUp] |
||||||
|
public void Setup() |
||||||
|
{ |
||||||
|
sampleLineOfData = "1.950,0.100,0.200,1.950,0.300,0.400,3.200,0.500,0.600,0.320"; |
||||||
|
getCommand = "P"; |
||||||
|
setCommand = "O"; |
||||||
|
|
||||||
|
_fakeComms = new FakeComms(); |
||||||
|
_vm = new AcroModeConfigVm(_fakeComms); |
||||||
|
} |
||||||
|
|
||||||
|
[Test] |
||||||
|
public void UpdateStringSentIsCorrect() |
||||||
|
{ |
||||||
|
_vm.PitchP = 1.0F; |
||||||
|
_vm.PitchI = 2.0F; |
||||||
|
_vm.PitchD = 3.0F; |
||||||
|
_vm.RollP = 5.0F; |
||||||
|
_vm.RollI = 6.0F; |
||||||
|
_vm.RollD = 7.0F; |
||||||
|
_vm.YawP = 8.0F; |
||||||
|
_vm.YawI = 9.0F; |
||||||
|
_vm.YawD = 10.0F; |
||||||
|
_vm.TransmitterFactor = 4.0F; |
||||||
|
|
||||||
|
_vm.UpdateCommand.Execute(null); |
||||||
|
|
||||||
|
Assert.AreEqual(1, _fakeComms.SentItems.Count); |
||||||
|
Assert.AreEqual("O5;6;7;1;2;3;8;9;10;4", _fakeComms.SentItems[0]); |
||||||
|
} |
||||||
|
} |
||||||
|
|
||||||
|
|
||||||
|
[TestFixture] |
||||||
|
public class AltitudeHoldVmTest : VmTestBase<AltitudeHoldConfigVm> |
||||||
|
{ |
||||||
|
|
||||||
|
[SetUp] |
||||||
|
public void Setup() |
||||||
|
{ |
||||||
|
sampleLineOfData = "0.800,0.200,0.300"; |
||||||
|
getCommand = "F"; |
||||||
|
setCommand = "E"; |
||||||
|
|
||||||
|
_fakeComms = new FakeComms(); |
||||||
|
_vm = new AltitudeHoldConfigVm(_fakeComms); |
||||||
|
} |
||||||
|
|
||||||
|
|
||||||
|
[Test] |
||||||
|
public void UpdateStringSentIsCorrect() |
||||||
|
{ |
||||||
|
_vm.P = 1.0F; |
||||||
|
_vm.I = 2.0F; |
||||||
|
_vm.D = 3.0F; |
||||||
|
|
||||||
|
_vm.UpdateCommand.Execute(null); |
||||||
|
|
||||||
|
Assert.AreEqual(1, _fakeComms.SentItems.Count); |
||||||
|
Assert.AreEqual("E1;3;2", _fakeComms.SentItems[0]); |
||||||
|
} |
||||||
|
|
||||||
|
[Test] |
||||||
|
// For whatever reason, for Altitude the properties are sent in P, D ,I |
||||||
|
// order, but received in P,I,D order |
||||||
|
public void UpdateStringReceivedPopulatesValuesCorrectly() |
||||||
|
{ |
||||||
|
_vm.Activate(); |
||||||
|
_fakeComms.FireLineRecieve(sampleLineOfData); |
||||||
|
|
||||||
|
Assert.AreEqual(0.8f, _vm.P); |
||||||
|
Assert.AreEqual(0.2f, _vm.I); |
||||||
|
Assert.AreEqual(0.3f, _vm.D); |
||||||
|
} |
||||||
|
|
||||||
|
|
||||||
|
} |
||||||
|
} |
@ -1,48 +1,44 @@ |
|||||||
using ArducopterConfigurator.PresentationModels; |
using ArducopterConfigurator; |
||||||
using NUnit.Framework; |
using NUnit.Framework; |
||||||
|
|
||||||
namespace ArducopterConfiguratorTest |
namespace ArducopterConfiguratorTest |
||||||
{ |
{ |
||||||
[TestFixture] |
public abstract class VmTestBase<T> where T : MonitorVm |
||||||
public class AltitudeHoldVmTest |
|
||||||
{ |
{ |
||||||
private FakeComms _fakeComms; |
protected T _vm; |
||||||
private AltitudeHoldConfigVm _vm; |
protected FakeComms _fakeComms; |
||||||
|
protected string sampleLineOfData; |
||||||
|
protected string getCommand; |
||||||
|
protected string setCommand; |
||||||
|
|
||||||
[SetUp] |
[Test] |
||||||
public void Setup() |
public void ActivateSendsCorrectCommand() |
||||||
{ |
{ |
||||||
_fakeComms = new FakeComms(); |
_vm.Activate(); |
||||||
_vm = new AltitudeHoldConfigVm(_fakeComms); |
Assert.AreEqual(1, _fakeComms.SentItems.Count); |
||||||
|
Assert.AreEqual(getCommand, _fakeComms.SentItems[0]); |
||||||
} |
} |
||||||
|
|
||||||
[Test] |
[Test] |
||||||
public void UpdateStringSentIsCorrect() |
public void ReceivedDataIgnoredWhenNotActive() |
||||||
{ |
{ |
||||||
_vm.P = 1.0F; |
bool inpcFired = false; |
||||||
_vm.I = 2.0F; |
_vm.PropertyChanged += delegate { inpcFired = true; }; |
||||||
_vm.D = 3.0F; |
|
||||||
|
|
||||||
_vm.UpdateCommand.Execute(null); |
|
||||||
|
|
||||||
Assert.AreEqual(1, _fakeComms.SentItems.Count); |
|
||||||
|
|
||||||
Assert.AreEqual("E1;3;2", _fakeComms.SentItems[0]); |
|
||||||
|
|
||||||
|
_fakeComms.FireLineRecieve(sampleLineOfData); |
||||||
|
Assert.False(inpcFired); |
||||||
} |
} |
||||||
|
|
||||||
[Test] |
[Test] |
||||||
// For whatever reason, for Altitude the properties are sent in P, D ,I |
public void UpdateStringReceivedPopulatesValues() |
||||||
// order, but received in P,I,D order |
|
||||||
public void UpdateStringReceivedPopulatesValuesCorrectly() |
|
||||||
{ |
{ |
||||||
_fakeComms.FireLineRecieve("F1;2;3"); |
bool inpcFired = false; |
||||||
|
_vm.PropertyChanged += delegate { inpcFired = true; }; |
||||||
Assert.AreEqual(1f, _vm.P); |
|
||||||
Assert.AreEqual(2f, _vm.I); |
|
||||||
Assert.AreEqual(3f, _vm.D); |
|
||||||
} |
|
||||||
|
|
||||||
|
_vm.Activate(); |
||||||
|
_fakeComms.FireLineRecieve(sampleLineOfData); |
||||||
|
|
||||||
|
Assert.True(inpcFired); |
||||||
|
} |
||||||
} |
} |
||||||
} |
} |
||||||
|
@ -0,0 +1,66 @@ |
|||||||
|
using ArducopterConfigurator.PresentationModels; |
||||||
|
using NUnit.Framework; |
||||||
|
|
||||||
|
namespace ArducopterConfiguratorTest |
||||||
|
{ |
||||||
|
[TestFixture] |
||||||
|
public class StableModeConfigVmTest : VmTestBase<StableModeConfigVm> |
||||||
|
{ |
||||||
|
|
||||||
|
[SetUp] |
||||||
|
public void Setup() |
||||||
|
{ |
||||||
|
sampleLineOfData = "1.950,0.100,0.200,1.950,0.300,0.400,3.200,0.500,0.600,0.320,1.00"; |
||||||
|
getCommand = "B"; |
||||||
|
setCommand = "A"; |
||||||
|
|
||||||
|
_fakeComms = new FakeComms(); |
||||||
|
_vm = new StableModeConfigVm(_fakeComms); |
||||||
|
} |
||||||
|
|
||||||
|
[Test] |
||||||
|
public void UpdateStringSentIsCorrect() |
||||||
|
{ |
||||||
|
_vm.PitchP = 1.0F; |
||||||
|
_vm.PitchI = 2.0F; |
||||||
|
_vm.PitchD = 3.0F; |
||||||
|
_vm.RollP = 5.0F; |
||||||
|
_vm.RollI = 6.0F; |
||||||
|
_vm.RollD = 7.0F; |
||||||
|
_vm.YawP = 8.0F; |
||||||
|
_vm.YawI = 9.0F; |
||||||
|
_vm.YawD = 10.0F; |
||||||
|
_vm.MagnetometerEnable = true; |
||||||
|
_vm.KPrate = 4.0F; |
||||||
|
|
||||||
|
_vm.UpdateCommand.Execute(null); |
||||||
|
|
||||||
|
|
||||||
|
Assert.AreEqual(1, _fakeComms.SentItems.Count); |
||||||
|
|
||||||
|
//A[KP Quad Roll];[KI Quad Roll];[KP RATE ROLL]; |
||||||
|
// [KP Quad Pitch];[KI Quad Pitch];[KP RATE PITCH]; |
||||||
|
// [KP Quad Yaw];[KI Quad Yaw];[KP Rate Yaw]; |
||||||
|
// [KP Rate];[Magneto] |
||||||
|
Assert.AreEqual("A5;6;7;1;2;3;8;9;10;4;1", _fakeComms.SentItems[0]); |
||||||
|
} |
||||||
|
|
||||||
|
[Test] |
||||||
|
public void UpdateStringReceivedPopulatesValuesCorrectly() |
||||||
|
{ |
||||||
|
_fakeComms.FireLineRecieve("B5;6;7;1;2;3;8;9;10;4;1"); |
||||||
|
|
||||||
|
Assert.AreEqual(1.0f, _vm.PitchP); |
||||||
|
Assert.AreEqual(2f, _vm.PitchI); |
||||||
|
Assert.AreEqual(3f, _vm.PitchD); |
||||||
|
Assert.AreEqual(5f, _vm.RollP); |
||||||
|
Assert.AreEqual(6f, _vm.RollI); |
||||||
|
Assert.AreEqual(7f, _vm.RollD); |
||||||
|
Assert.AreEqual(8f, _vm.YawP); |
||||||
|
Assert.AreEqual(9f, _vm.YawI); |
||||||
|
Assert.AreEqual(10f, _vm.YawD); |
||||||
|
Assert.AreEqual(1f, _vm.MagnetometerEnable); |
||||||
|
Assert.AreEqual(4f, _vm.KPrate); |
||||||
|
} |
||||||
|
} |
||||||
|
} |
Loading…
Reference in new issue