Skip to content

Commit

Permalink
feat(params): implement the feature to load parameters from IConfigur…
Browse files Browse the repository at this point in the history
  • Loading branch information
asvol committed Jan 19, 2024
1 parent 76dc98e commit 8f2a4d3
Show file tree
Hide file tree
Showing 13 changed files with 324 additions and 156 deletions.
97 changes: 79 additions & 18 deletions src/Asv.Mavlink.Test/Devices/Base/BaseDevicesTest.cs
Original file line number Diff line number Diff line change
Expand Up @@ -41,8 +41,16 @@ public Task ClientDeviceConfigArgumentNullExceptionTest()
{
var link = new VirtualMavlinkConnection();

var clientId = new MavlinkClientIdentity
{
SystemId = 1,
ComponentId = 2,
TargetSystemId = 3,
TargetComponentId = 4
};

var clientDevice = new AbstractClientDevice(link.Client,
new MavlinkClientIdentity(),
clientId,
new ClientDeviceConfig
{
Heartbeat = null
Expand Down Expand Up @@ -161,9 +169,15 @@ public void ClientDeviceSequenceArgumentNullExceptionTest()
Assert.Throws<ArgumentNullException>(() =>
{
var link = new VirtualMavlinkConnection();

var clientId = new MavlinkClientIdentity
{
SystemId = 1,
ComponentId = 2,
TargetSystemId = 3,
TargetComponentId = 4
};
var clientDevice = new AbstractClientDevice(link.Client,
new MavlinkClientIdentity(),
clientId,
new ClientDeviceConfig(),
null,
Scheduler.Default);
Expand All @@ -179,11 +193,18 @@ public void ClientDeviceSequenceArgumentNullExceptionTest()
public async Task BaseDevicesStatusTextTest(string messageText)
{
var link = new VirtualMavlinkConnection();

var clientId = new MavlinkClientIdentity
{
SystemId = 1,
ComponentId = 2,
TargetSystemId = 3,
TargetComponentId = 4
};
var serverId = new MavlinkIdentity(clientId.TargetSystemId, clientId.TargetComponentId);
var serverDevice = new ServerDevice(link.Server, new PacketSequenceCalculator(),
new MavlinkIdentity(), new ServerDeviceConfig(), Scheduler.Default);
serverId, new ServerDeviceConfig(), Scheduler.Default);

var clientDevice = new AbstractClientDevice(link.Client, new MavlinkClientIdentity(),
var clientDevice = new AbstractClientDevice(link.Client, clientId,
new ClientDeviceConfig(), new PacketSequenceCalculator(), Scheduler.Default);

serverDevice.Start();
Expand All @@ -205,11 +226,19 @@ public async Task BaseDevicesStatusTextTest(string messageText)
public async Task BaseDevicesStatusTextOverloadTest()
{
var link = new VirtualMavlinkConnection();

var clientId = new MavlinkClientIdentity
{
SystemId = 1,
ComponentId = 2,
TargetSystemId = 3,
TargetComponentId = 4
};
var serverId = new MavlinkIdentity(clientId.TargetSystemId, clientId.TargetComponentId);

var serverDevice = new ServerDevice(link.Server, new PacketSequenceCalculator(),
new MavlinkIdentity(), new ServerDeviceConfig(), Scheduler.Default);
serverId, new ServerDeviceConfig(), Scheduler.Default);

var clientDevice = new AbstractClientDevice(link.Client, new MavlinkClientIdentity(),
var clientDevice = new AbstractClientDevice(link.Client, clientId,
new ClientDeviceConfig(), new PacketSequenceCalculator(), Scheduler.Default);

serverDevice.Start();
Expand Down Expand Up @@ -253,9 +282,17 @@ public async Task BaseDevicesHeartbeatConnectionQualityTest()
int packetsCount = 0;

var link = new VirtualMavlinkConnection(_ => true, _ => ++packetsCount % 2 == 1);
var clientId = new MavlinkClientIdentity
{
SystemId = 1,
ComponentId = 2,
TargetSystemId = 3,
TargetComponentId = 4
};
var serverId = new MavlinkIdentity(clientId.TargetSystemId, clientId.TargetComponentId);

var serverDevice = new ServerDevice(link.Server, new PacketSequenceCalculator(),
new MavlinkIdentity(),
serverId,
new ServerDeviceConfig()
{
Heartbeat = new MavlinkHeartbeatServerConfig()
Expand All @@ -265,7 +302,7 @@ public async Task BaseDevicesHeartbeatConnectionQualityTest()
},
Scheduler.Default);

var clientDevice = new AbstractClientDevice(link.Client, new MavlinkClientIdentity(),
var clientDevice = new AbstractClientDevice(link.Client, clientId,
new ClientDeviceConfig(), new PacketSequenceCalculator(), Scheduler.Default);

serverDevice.Start();
Expand All @@ -292,11 +329,19 @@ public async Task BaseDevicesHeartbeatConnectionStateTest()
bool canSend = true;

var link = new VirtualMavlinkConnection(_ => canSend, _ => canSend);

var clientId = new MavlinkClientIdentity
{
SystemId = 1,
ComponentId = 2,
TargetSystemId = 3,
TargetComponentId = 4
};
var serverId = new MavlinkIdentity(clientId.TargetSystemId, clientId.TargetComponentId);

var serverDevice = new ServerDevice(link.Server, new PacketSequenceCalculator(),
new MavlinkIdentity(), new ServerDeviceConfig(), Scheduler.Default);
serverId, new ServerDeviceConfig(), Scheduler.Default);

var clientDevice = new AbstractClientDevice(link.Client, new MavlinkClientIdentity(),
var clientDevice = new AbstractClientDevice(link.Client, clientId,
new ClientDeviceConfig(), new PacketSequenceCalculator(), Scheduler.Default);

serverDevice.Start();
Expand Down Expand Up @@ -346,15 +391,23 @@ public async Task BaseDevicesHeartbeatConnectionStateTest()
public async Task BaseDevicesCustomModeTest()
{
var link = new VirtualMavlinkConnection();
var clientId = new MavlinkClientIdentity
{
SystemId = 1,
ComponentId = 2,
TargetSystemId = 3,
TargetComponentId = 4
};
var serverId = new MavlinkIdentity(clientId.TargetSystemId, clientId.TargetComponentId);

var mode = 23;

var serverDevice = new ServerDevice(link.Server, new PacketSequenceCalculator(),
new MavlinkIdentity(), new ServerDeviceConfig(), Scheduler.Default);
serverId, new ServerDeviceConfig(), Scheduler.Default);

serverDevice.Heartbeat.Set(_ => _.CustomMode = (uint)mode);

var clientDevice = new AbstractClientDevice(link.Client, new MavlinkClientIdentity(),
var clientDevice = new AbstractClientDevice(link.Client, clientId,
new ClientDeviceConfig(), new PacketSequenceCalculator(), Scheduler.Default);

serverDevice.Start();
Expand All @@ -380,13 +433,21 @@ public async Task BaseDevicesPacketsLossTest()
int lostPacketsCount = 4;

var link = new VirtualMavlinkConnection(_ => true,_ => ++packetsCount > lostPacketsCount);
var clientId = new MavlinkClientIdentity
{
SystemId = 1,
ComponentId = 2,
TargetSystemId = 3,
TargetComponentId = 4
};
var serverId = new MavlinkIdentity(clientId.TargetSystemId, clientId.TargetComponentId);

var serverDevice = new ServerDevice(link.Server, new PacketSequenceCalculator(),
new MavlinkIdentity (13,13), new ServerDeviceConfig(),
serverId, new ServerDeviceConfig(),
Scheduler.Default);

var clientDevice = new AbstractClientDevice(link.Client,
new MavlinkClientIdentity { ComponentId = 1, SystemId = 1, TargetComponentId = 13, TargetSystemId = 13},
clientId,
new ClientDeviceConfig(), new PacketSequenceCalculator(), Scheduler.Default);

serverDevice.Start();
Expand Down
39 changes: 32 additions & 7 deletions src/Asv.Mavlink.Test/Microservices/AdsbVehicle/AdsbVehicleTest.cs
Original file line number Diff line number Diff line change
Expand Up @@ -14,17 +14,25 @@ public class AdsbVehicleTest : DisposableOnceWithCancel
public async Task Check_Single_Adsb_Vehicle()
{
var link = new VirtualMavlinkConnection();
var clientId = new MavlinkClientIdentity
{
SystemId = 1,
ComponentId = 2,
TargetSystemId = 3,
TargetComponentId = 4
};
var serverId = new MavlinkIdentity(clientId.TargetSystemId, clientId.TargetComponentId);

var server = new AdsbServerDevice(
link.Server,
new PacketSequenceCalculator(),
new MavlinkIdentity (2,2),
serverId,
new AdsbServerDeviceConfig(),
Scheduler.Default);

var client = new AdsbClientDevice(
link.Client,
new MavlinkClientIdentity { ComponentId = 1, SystemId = 1, TargetComponentId = 2, TargetSystemId = 2 },
clientId,
new PacketSequenceCalculator(),
new AdsbClientDeviceConfig(), Scheduler.Default);

Expand Down Expand Up @@ -71,16 +79,25 @@ public async Task Check_Multiple_Adsb_Vehicles()
{
var link = new VirtualMavlinkConnection();

var clientId = new MavlinkClientIdentity
{
SystemId = 1,
ComponentId = 2,
TargetSystemId = 3,
TargetComponentId = 4
};
var serverId = new MavlinkIdentity(clientId.TargetSystemId, clientId.TargetComponentId);

var server = new AdsbServerDevice(
link.Server,
new PacketSequenceCalculator(),
new MavlinkIdentity (2,2),
serverId,
new AdsbServerDeviceConfig(),
Scheduler.Default);

var client = new AdsbClientDevice(
link.Client,
new MavlinkClientIdentity { ComponentId = 1, SystemId = 1, TargetComponentId = 2, TargetSystemId = 2 },
clientId,
new PacketSequenceCalculator(),
new AdsbClientDeviceConfig(), Scheduler.Default);

Expand Down Expand Up @@ -149,17 +166,25 @@ await server.Adsb.Send(_ =>
public async Task Check_If_Old_Vehicles_Are_Deleted()
{
var link = new VirtualMavlinkConnection();

var clientId = new MavlinkClientIdentity
{
SystemId = 1,
ComponentId = 2,
TargetSystemId = 3,
TargetComponentId = 4
};
var serverId = new MavlinkIdentity(clientId.TargetSystemId, clientId.TargetComponentId);

var server = new AdsbServerDevice(
link.Server,
new PacketSequenceCalculator(),
new MavlinkIdentity (2,2),
serverId,
new AdsbServerDeviceConfig(),
Scheduler.Default);

var client = new AdsbClientDevice(
link.Client,
new MavlinkClientIdentity { ComponentId = 1, SystemId = 1, TargetComponentId = 2, TargetSystemId = 2 },
clientId,
new PacketSequenceCalculator(),
new AdsbClientDeviceConfig(), Scheduler.Default);

Expand Down
25 changes: 21 additions & 4 deletions src/Asv.Mavlink.Test/Microservices/AsvGbs/AsvGbsTest.cs
Original file line number Diff line number Diff line change
Expand Up @@ -28,9 +28,18 @@ public AsvGbsTest(ITestOutputHelper output)
public async Task Server_Send_Status_And_Client_Check_It(int lat,int lon,int alt)
{
var link = new VirtualMavlinkConnection();
var clientId = new MavlinkClientIdentity
{
SystemId = 1,
ComponentId = 2,
TargetSystemId = 3,
TargetComponentId = 4
};
var serverId = new MavlinkIdentity(clientId.TargetSystemId, clientId.TargetComponentId);

var cfg = new InMemoryConfiguration();
var mode = AsvGbsCustomMode.AsvGbsCustomModeAuto;
IGbsServerDevice serverDevice = new GbsServerDevice(link.Server, new MavlinkIdentity(),new PacketSequenceCalculator(),Scheduler.Default,new GbsServerDeviceConfig(), new List<IMavParamTypeMetadata>(), new MavParamCStyleEncoding(),cfg);
IGbsServerDevice serverDevice = new GbsServerDevice(link.Server, serverId,new PacketSequenceCalculator(),Scheduler.Default,new GbsServerDeviceConfig(), new List<IMavParamTypeMetadata>(), new MavParamCStyleEncoding(),cfg);
serverDevice.Gbs.AccuracyMeter.OnNext(0.15);
serverDevice.Gbs.ObservationSec.OnNext(1);
serverDevice.Gbs.DgpsRate.OnNext(2);
Expand All @@ -45,7 +54,7 @@ public async Task Server_Send_Status_And_Client_Check_It(int lat,int lon,int alt
serverDevice.Gbs.CustomMode.OnNext(mode);
serverDevice.Gbs.Position.OnNext(new GeoPoint(lat,lon,alt));

IGbsClientDevice clientDevice = new GbsClientDevice(link.Client,new MavlinkClientIdentity(), new PacketSequenceCalculator(), new GbsClientDeviceConfig(), Scheduler.Default);
IGbsClientDevice clientDevice = new GbsClientDevice(link.Client,clientId, new PacketSequenceCalculator(), new GbsClientDeviceConfig(), Scheduler.Default);
serverDevice.Heartbeat.Set(_ => _.CustomMode = (uint)mode);
serverDevice.Gbs.Base.Set(_ =>
{
Expand Down Expand Up @@ -75,9 +84,17 @@ public async Task Server_Send_Status_And_Client_Check_It(int lat,int lon,int alt
public async Task Client_Call_Command_And_Server_Catch_It(float duration,float accuracy, MavResult result)
{
var link = new VirtualMavlinkConnection();
var clientId = new MavlinkClientIdentity
{
SystemId = 1,
ComponentId = 2,
TargetSystemId = 3,
TargetComponentId = 4
};
var serverId = new MavlinkIdentity(clientId.TargetSystemId, clientId.TargetComponentId);

var called = false;
var serverDevice = new GbsServerDevice(link.Server, new MavlinkIdentity(),new PacketSequenceCalculator(),Scheduler.Default, new GbsServerDeviceConfig(), new List<IMavParamTypeMetadata>(), new MavParamCStyleEncoding(),new InMemoryConfiguration());
var serverDevice = new GbsServerDevice(link.Server, serverId,new PacketSequenceCalculator(),Scheduler.Default, new GbsServerDeviceConfig(), new List<IMavParamTypeMetadata>(), new MavParamCStyleEncoding(),new InMemoryConfiguration());
serverDevice.Gbs.StartAutoMode = (dur, acc, cancel) =>
{
called = true;
Expand All @@ -98,7 +115,7 @@ public async Task Client_Call_Command_And_Server_Catch_It(float duration,float a
serverDevice.Gbs.ImesSatellites.OnNext(10);
serverDevice.Gbs.CustomMode.OnNext(AsvGbsCustomMode.AsvGbsCustomModeIdle);
serverDevice.Gbs.Position.OnNext(GeoPoint.Zero);
var clientDevice = new GbsClientDevice(link.Client,new MavlinkClientIdentity(), new PacketSequenceCalculator(), new GbsClientDeviceConfig(), Scheduler.Default);
var clientDevice = new GbsClientDevice(link.Client,clientId, new PacketSequenceCalculator(), new GbsClientDeviceConfig(), Scheduler.Default);
serverDevice.Start();
clientDevice.WaitUntilConnect();
await Task.Delay(2000);
Expand Down
26 changes: 17 additions & 9 deletions src/Asv.Mavlink.Test/Microservices/AsvSdr/AsvSdrExTests.cs
Original file line number Diff line number Diff line change
Expand Up @@ -22,19 +22,27 @@ public class AsvSdrExTests
private async Task<(IAsvSdrClientEx, IAsvSdrServerEx)> SetUpConnection()
{
var link = new VirtualMavlinkConnection();
var mavlinkClientIdentity = new MavlinkClientIdentity() { SystemId = 1, ComponentId = 1, TargetSystemId = 2, TargetComponentId = 2 };
var heartBeatClient = new HeartbeatClient(link.Client, mavlinkClientIdentity, new PacketSequenceCalculator(), new HeartbeatClientConfig(), Scheduler.Default);
var commandClient = new CommandClient(link.Client, mavlinkClientIdentity, new PacketSequenceCalculator(), new CommandProtocolConfig());
var asvSdrClient = new AsvSdrClient(link.Client, mavlinkClientIdentity, new PacketSequenceCalculator());
var clientId = new MavlinkClientIdentity
{
SystemId = 1,
ComponentId = 2,
TargetSystemId = 3,
TargetComponentId = 4
};
var serverId = new MavlinkIdentity(clientId.TargetSystemId, clientId.TargetComponentId);


var heartBeatClient = new HeartbeatClient(link.Client, clientId, new PacketSequenceCalculator(), new HeartbeatClientConfig(), Scheduler.Default);
var commandClient = new CommandClient(link.Client, clientId, new PacketSequenceCalculator(), new CommandProtocolConfig());
var asvSdrClient = new AsvSdrClient(link.Client, clientId, new PacketSequenceCalculator());
var asvSdrClientEx = new AsvSdrClientEx(asvSdrClient, heartBeatClient, commandClient, new AsvSdrClientExConfig());

var pkt = new PacketSequenceCalculator();
var MavlinkIdentity = new MavlinkIdentity(2, 2 );
var heartBeatServer = new HeartbeatServer(link.Server, pkt, MavlinkIdentity, new MavlinkHeartbeatServerConfig(), Scheduler.Default);
var commandServer = new CommandServer(link.Server, pkt, MavlinkIdentity, Scheduler.Default);
var heartBeatServer = new HeartbeatServer(link.Server, pkt, serverId, new MavlinkHeartbeatServerConfig(), Scheduler.Default);
var commandServer = new CommandServer(link.Server, pkt, serverId, Scheduler.Default);
var commandLongServerEx = new CommandLongServerEx(commandServer);
var status = new StatusTextServer(link.Server, pkt, MavlinkIdentity, new StatusTextLoggerConfig(), Scheduler.Default);
var asvSdrServer = new AsvSdrServer(link.Server, MavlinkIdentity, new AsvSdrServerConfig(), pkt, Scheduler.Default);
var status = new StatusTextServer(link.Server, pkt, serverId, new StatusTextLoggerConfig(), Scheduler.Default);
var asvSdrServer = new AsvSdrServer(link.Server, serverId, new AsvSdrServerConfig(), pkt, Scheduler.Default);
var asvSdrServerEx = new AsvSdrServerEx(asvSdrServer,status, heartBeatServer, commandLongServerEx);

heartBeatServer.Start();
Expand Down
20 changes: 11 additions & 9 deletions src/Asv.Mavlink.Test/Microservices/AsvSdr/AsvSdrTest.cs
Original file line number Diff line number Diff line change
Expand Up @@ -20,18 +20,20 @@ public AsvSdrTest(ITestOutputHelper output)
private void SetupClientServer(out IAsvSdrServer serverSdr, out IAsvSdrClient clientSdr)
{
var link = new VirtualMavlinkConnection();
var clientId = new MavlinkClientIdentity
{
SystemId = 1,
ComponentId = 2,
TargetSystemId = 3,
TargetComponentId = 4
};
var serverId = new MavlinkIdentity(clientId.TargetSystemId, clientId.TargetComponentId);

serverSdr = new AsvSdrServer(link.Server,
new MavlinkIdentity (2, 2), new AsvSdrServerConfig(),
serverId, new AsvSdrServerConfig(),
new PacketSequenceCalculator(), Scheduler.Default);

clientSdr = new AsvSdrClient(link.Client, new MavlinkClientIdentity
{
SystemId = 13,
ComponentId = 13,
TargetSystemId = 2,
TargetComponentId = 2
},
new PacketSequenceCalculator());
clientSdr = new AsvSdrClient(link.Client,clientId, new PacketSequenceCalculator());

serverSdr.Start();
}
Expand Down
Loading

0 comments on commit 8f2a4d3

Please sign in to comment.