How to connect to SITL with Asv.Mavlink library
Almost everything is similar to the virtual connection approach, but there are some key differences.
Copy all the code from here
Change
var cancel = new CancellationTokenSource(TimeSpan.FromSeconds(10), TimeProvider.System);
to
var cancel = new CancellationTokenSource(TimeSpan.FromSeconds(200), TimeProvider.System);
Change
var link = protocol.CreateVirtualConnection();
to
var router = protocol.CreateRouter("router");
After var router = protocol.CreateRouter("router");
add
router.AddTcpClientPort(p =>
{
p.Host = "127.0.0.1";
p.Port = 5760; // change
});
Change
var identity = new MavlinkClientIdentity(1,2,3,4);
to
var identity = new MavlinkClientIdentity(2,3,1,1);
Note: TargetSystemId and TargetComponentId for Ardu SITL by default is 1
Delete everything after ArduCopter creation
Add code:
var called = 0;
arduCopter.Heartbeat.RawHeartbeat.Subscribe(p =>
{
if (p is null)
{
return;
}
Console.WriteLine($"Heartbeat type: {p.Type}, Heartbeat baseMode: {p.BaseMode}");
if (called != 20)
{
called++;
return;
}
tcs.TrySetResult(p);
});
await tcs.Task;
This code catches first 20 heartbeat packages
Proper Output
Heartbeat type: MavTypeQuadrotor, Heartbeat baseMode: 81
Heartbeat type: MavTypeQuadrotor, Heartbeat baseMode: 81
Heartbeat type: MavTypeQuadrotor, Heartbeat baseMode: 81
Heartbeat type: MavTypeQuadrotor, Heartbeat baseMode: 81
Heartbeat type: MavTypeQuadrotor, Heartbeat baseMode: 81
Heartbeat type: MavTypeQuadrotor, Heartbeat baseMode: 81
Heartbeat type: MavTypeQuadrotor, Heartbeat baseMode: 81
Heartbeat type: MavTypeQuadrotor, Heartbeat baseMode: 81
Heartbeat type: MavTypeQuadrotor, Heartbeat baseMode: 81
Heartbeat type: MavTypeQuadrotor, Heartbeat baseMode: 81
Heartbeat type: MavTypeQuadrotor, Heartbeat baseMode: 81
Heartbeat type: MavTypeQuadrotor, Heartbeat baseMode: 81
Heartbeat type: MavTypeQuadrotor, Heartbeat baseMode: 81
Heartbeat type: MavTypeQuadrotor, Heartbeat baseMode: 81
Heartbeat type: MavTypeQuadrotor, Heartbeat baseMode: 81
Heartbeat type: MavTypeQuadrotor, Heartbeat baseMode: 81
Heartbeat type: MavTypeQuadrotor, Heartbeat baseMode: 81
Heartbeat type: MavTypeQuadrotor, Heartbeat baseMode: 81
Heartbeat type: MavTypeQuadrotor, Heartbeat baseMode: 81
Heartbeat type: MavTypeQuadrotor, Heartbeat baseMode: 81
Heartbeat type: MavTypeQuadrotor, Heartbeat baseMode: 81
Process finished with exit code 0.
Full code
using System.Collections.Immutable;
using Asv.Common;
using Asv.IO;
using Asv.Mavlink;
using Asv.Mavlink.Minimal;
using R3;
var tcs = new TaskCompletionSource<HeartbeatPayload>();
var cancel = new CancellationTokenSource(TimeSpan.FromSeconds(200), TimeProvider.System);
cancel.Token.Register(() => tcs.TrySetCanceled());
var protocol = Protocol.Create(builder =>
{
builder.RegisterMavlinkV2Protocol();
builder.Features.RegisterBroadcastFeature<MavlinkMessage>();
builder.Formatters.RegisterSimpleFormatter();
});
var router = protocol.CreateRouter("router");
router.AddTcpClientPort(p =>
{
p.Host = "127.0.0.1";
p.Port = 5760;
});
var identity = new MavlinkClientIdentity(2,3,1,1);
var clientSeq = new PacketSequenceCalculator();
var clientCore = new CoreServices(
router,
clientSeq,
null,
null,
new DefaultMeterFactory()
);
var deviceId = new MavlinkClientDeviceId("copter", identity);
var config = new VehicleClientDeviceConfig();
var arduCopter = new ArduCopterClientDevice(
deviceId,
config,
ImmutableArray<IClientDeviceExtender>.Empty,
clientCore
);
var called = 0;
arduCopter.Heartbeat.RawHeartbeat.Subscribe(p =>
{
if (p is null)
{
return;
}
Console.WriteLine($"Heartbeat type: {p.Type}, Heartbeat baseMode: {p.BaseMode}");
if (called != 20)
{
called++;
return;
}
tcs.TrySetResult(p);
});
await tcs.Task;