Asv Mavlink Help

With Ardu SITL

Ardu SITL Installation

You have two options of the SITL installation:

  1. Through docker

  2. Through .exe (note: windows only)

With Docker

Note: we assume that you already have docker installed.

  1. Open your console and write. (note: you may also need to write sudo before every command on Unix systems)

docker pull flurps1/asv-sitl
  1. Run container with port 5760 (note: you can select another free port)

docker run -p 5760:5760 flurps1/asv-sitl

With .exe

Note: only for windows! If you have any problems with this SITL it is better to use docker

  1. Download files from here and put them in any folder.

  2. Change all .elf to .exe

  3. Create a .bat file in the folder with name run_copter.bat.

  4. Edit this file with a notepad and add code:

ArduCopter.exe -M+ -O55.2905802,61.6063891,191.303759999999,0 -s10 --uartA tcp:0 rm logs
  1. Run .bat file.

  2. Now SITL is online.

    image

A lot is similar to the virtual connection approach, but there are some key differences.

Repeat up to this step

Setup task completion source and cancellation token

  1. Create a task completion source. You'll need it to wait for a response from the server.

var tcs = new TaskCompletionSource<HeartbeatPayload>();
  1. Create a cancellation token source with a timeout. The cancellation token will trigger after 20 seconds. You can change this by setting a different time span.

using var cancel = new CancellationTokenSource(TimeSpan.FromSeconds(20), TimeProvider.System);
  1. Register a delegate that will be called when the cancellation token is canceled. This will stop tcs from running in a loop when the token fails.

cancel.Token.Register(() => tcs.TrySetCanceled());

Create router

  1. Create protocol factory

var protocol = Protocol.Create(builder => { builder.RegisterMavlinkV2Protocol(); builder.Features.RegisterBroadcastFeature<MavlinkMessage>(); builder.Formatters.RegisterSimpleFormatter(); });
  1. Create router

await using var router = protocol.CreateRouter("ROUTER");
  1. Add port with the drone connection data

router.AddTcpClientPort(p => { p.Host = "127.0.0.1"; p.Port = 5760; });

Device explorer creation

We need a device explorer to search for the drone

  1. Create packet sequence calculator

var seq = new PacketSequenceCalculator();
  1. Create id of the system that will search for the drone

var seq = new PacketSequenceCalculator();
  1. Create device explorer

await using var deviceExplorer = DeviceExplorer.Create(router, builder => { builder.SetConfig(new ClientDeviceBrowserConfig() { DeviceTimeoutMs = 1000, DeviceCheckIntervalMs = 30_000, }); builder.Factories.RegisterDefaultDevices( new MavlinkIdentity(identity.SystemId, identity.ComponentId), seq, new InMemoryConfiguration()); });

Find the device

  1. Create variable for the client device

IClientDevice? drone = null;
  1. Subscribe to search for the drone

using var sub = deviceExplorer.Devices .ObserveAdd() .Take(1) .Subscribe(kvp => { drone = kvp.Value.Value; tcs.TrySetResult(); });
  1. Wait until the subscription locates a drone

await tcs.Task;
  1. Check if the drone was successfully found

if (drone is null) { throw new Exception("Drone not found"); }

Initialize the drone

  1. Create new task completion source

tcs = new TaskCompletionSource();
  1. Subscribe to stop completion source when the client is initialized

using var sub2 = drone.State .Subscribe(x => { if (x != ClientDeviceState.Complete) { return; } tcs.TrySetResult(); });
  1. Wait until the drone is initialized

await tcs.Task;

Search for the heartbeat client

  1. Get heartbeat microservice

await using var heartbeat = drone?.GetMicroservice<IHeartbeatClient>();
  1. Check if the heartbeat client was successfully found

if (heartbeat is null) { throw new Exception("No control client found"); }

Test the connection

  1. Create new task completion source

tcs = new TaskCompletionSource();
  1. Create counter to limit application's lifetime

var count = 0;
  1. Subscribe to the RawHeartbeat pipe to show heartbeat packages This code catches first 20 heartbeat packages

using var sub3 = heartbeat.RawHeartbeat .ThrottleLast(TimeSpan.FromMilliseconds(100)) .Subscribe(p => { if (p is null) { return; } Console.WriteLine($"Heartbeat type: {p.Type}, Heartbeat baseMode: {p.BaseMode}"); if (count >= 19) { tcs.TrySetResult(); return; } count++; });
  1. Wait until the stop is called manually in the subscription

await tcs.Task;

Proper Output Example

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 Asv.Cfg; using Asv.IO; using Asv.Mavlink; using ObservableCollections; using R3; // Setup var tcs = new TaskCompletionSource(); using var cts = new CancellationTokenSource(TimeSpan.FromSeconds(20), TimeProvider.System); await using var s = cts.Token.Register(() => tcs.TrySetCanceled()); // // Router creation var protocol = Protocol.Create(builder => { builder.RegisterMavlinkV2Protocol(); builder.Features.RegisterBroadcastFeature<MavlinkMessage>(); builder.Formatters.RegisterSimpleFormatter(); }); await using var router = protocol.CreateRouter("ROUTER"); router.AddTcpClientPort(p => { p.Host = "127.0.0.1"; p.Port = 5760; }); // // Device explorer creation var seq = new PacketSequenceCalculator(); var identity = new MavlinkIdentity(255, 255); await using var deviceExplorer = DeviceExplorer.Create(router, builder => { builder.SetConfig(new ClientDeviceBrowserConfig() { DeviceTimeoutMs = 1000, DeviceCheckIntervalMs = 30_000, }); builder.Factories.RegisterDefaultDevices( new MavlinkIdentity(identity.SystemId, identity.ComponentId), seq, new InMemoryConfiguration()); }); // // Device search IClientDevice? drone = null; using var sub = deviceExplorer.Devices .ObserveAdd() .Take(1) .Subscribe(kvp => { drone = kvp.Value.Value; tcs.TrySetResult(); }); await tcs.Task; if (drone is null) { throw new Exception("Drone not found"); } // // Drone init tcs = new TaskCompletionSource(); using var sub2 = drone.State .Subscribe(x => { if (x != ClientDeviceState.Complete) { return; } tcs.TrySetResult(); }); await tcs.Task; // // Heartbeat client search await using var heartbeat = drone?.GetMicroservice<IHeartbeatClient>(); if (heartbeat is null) { throw new Exception("No control client found"); } // // Test tcs = new TaskCompletionSource(); var count = 0; using var sub3 = heartbeat.RawHeartbeat .ThrottleLast(TimeSpan.FromMilliseconds(100)) .Subscribe(p => { if (p is null) { return; } Console.WriteLine($"Heartbeat type: {p.Type}, Heartbeat baseMode: {p.BaseMode}"); if (count >= 19) { tcs.TrySetResult(); return; } count++; }); await tcs.Task; //
Last modified: 23 May 2025