Class Vehicle
Logical handle to one MAVLink vehicle: a typed view of its telemetry plus async command helpers built on the canonical MAVLink command pattern (COMMAND_LONG → race ACK against state-change HEARTBEAT, with timeout).
Vehicle is a consumer of MavlinkConnection — it subscribes to the connection's typed events in its constructor and filters by the target SystemId/ComponentId. Multiple Vehicles can in principle share one Connection (they each filter for their own sender), though our factories create one Vehicle per Connection for simplicity.
Thread model. State writes happen on the connection's receive thread. Reads are eventually-consistent — for telemetry display this is fine. StateChanged fires synchronously on the receive thread; consumers must marshal to their UI thread themselves.
Metadata.Id and Name are opt-in, mutable, never read by the library — set them from your fleet/registry if you want them to follow the vehicle around.
public abstract class Vehicle : IAsyncDisposable, IStateObservable
- Inheritance
-
Vehicle
- Implements
- Derived
- Inherited Members
Constructors
Vehicle(IMavlinkConnection, byte, byte, bool, TimeSpan?, TimeSpan?, ILogger<Vehicle>?)
protected Vehicle(IMavlinkConnection connection, byte targetSystemId, byte targetComponentId, bool ownsConnection = false, TimeSpan? heartbeatTimeout = null, TimeSpan? commandTimeout = null, ILogger<Vehicle>? logger = null)
Parameters
connectionIMavlinkConnectionThe transport. Subscribes to its typed events.
targetSystemIdbyteSender system id this Vehicle accepts messages from.
targetComponentIdbyteSender component id this Vehicle accepts messages from.
ownsConnectionboolWhen true, DisposeAsync() also disposes the connection. Use false when sharing a connection across multiple Vehicles.
heartbeatTimeoutTimeSpan?Window in which a heartbeat must arrive for LinkUp to stay true.
commandTimeoutTimeSpan?How long a COMMAND_LONG may wait for ACK + state change before resolving as Sent/Timeout. Defaults to 6 s — the PX4-friendly value.
loggerILogger<Vehicle>Optional. Null = no logging.
Properties
Alt
Altitude in metres above mean sea level, updated from GLOBAL_POSITION_INT.
public double Alt { get; }
Property Value
Armed
Armed bit from the latest HEARTBEAT's base_mode.
public bool Armed { get; }
Property Value
Battery
Battery remaining as a percentage (0–100), updated from SYS_STATUS.
public double Battery { get; }
Property Value
ComponentId
MAVLink component id of this vehicle's autopilot (typically 1).
public byte ComponentId { get; }
Property Value
ConnectionString
Connection string the underlying transport was opened with, or null if unknown.
public string? ConnectionString { get; init; }
Property Value
DeviceId
Pretty identifier: sys{SystemId}-comp{ComponentId}.
public string DeviceId { get; }
Property Value
FenceOpaqueId
On-vehicle geofence-plan id from MISSION_CURRENT.fence_id. Same
semantics as MissionOpaqueId.
public uint FenceOpaqueId { get; }
Property Value
GpsFix
GPS fix type, updated from GPS_RAW_INT.
public GpsFixType GpsFix { get; }
Property Value
- GpsFixType
Hdg
Heading in degrees (0–360), updated from GLOBAL_POSITION_INT.
public double Hdg { get; }
Property Value
Id
Opt-in application-assigned identifier. The library never reads this — set it from your fleet/registry.
public string? Id { get; set; }
Property Value
LandedState
Landed/in-air state, updated from EXTENDED_SYS_STATE.
public MavLandedState LandedState { get; }
Property Value
- MavLandedState
LastHeartbeatAt
UTC timestamp of the most recent HEARTBEAT, or MinValue if none received yet.
public DateTime LastHeartbeatAt { get; }
Property Value
Lat
Latitude in degrees (WGS-84), updated from GLOBAL_POSITION_INT.
public double Lat { get; }
Property Value
LinkUp
True iff a HEARTBEAT was received within the heartbeat-timeout window.
public bool LinkUp { get; }
Property Value
Lon
Longitude in degrees (WGS-84), updated from GLOBAL_POSITION_INT.
public double Lon { get; }
Property Value
MissionCurrentSeq
Current mission item sequence (from MISSION_CURRENT), or -1 if
no MISSION_CURRENT has been received yet.
public int MissionCurrentSeq { get; }
Property Value
MissionOpaqueId
On-vehicle waypoint-plan id from MISSION_CURRENT.mission_id. 0
means "no plan loaded" or "vehicle doesn't support change-detection ids" per spec.
Compare against the value cached after upload/download to detect on-vehicle plan changes.
public uint MissionOpaqueId { get; }
Property Value
MissionReachedCount
Total number of MISSION_ITEM_REACHED events seen since this Vehicle
was constructed. Increments once per reached waypoint.
public int MissionReachedCount { get; }
Property Value
MissionState
Mission-execution state (Active / Paused / Complete / …) from
MISSION_CURRENT.mission_state.
public MissionState MissionState { get; }
Property Value
- MissionState
MissionTotal
Total number of mission items reported by the vehicle (from MISSION_CURRENT's
total field), or -1 if not received yet or the vehicle didn't include
the optional extension byte.
public int MissionTotal { get; }
Property Value
Mode
Human-readable PX4 mode label (e.g. AUTO.LOITER) parsed from custom_mode.
public string Mode { get; }
Property Value
Name
Opt-in display name. The library never reads this — set it from your fleet/registry.
public string? Name { get; set; }
Property Value
RallyOpaqueId
On-vehicle rally-point-plan id from MISSION_CURRENT.rally_points_id.
Same semantics as MissionOpaqueId.
public uint RallyOpaqueId { get; }
Property Value
Sats
Number of GPS satellites visible, updated from GPS_RAW_INT.
public int Sats { get; }
Property Value
SystemId
MAVLink system id of this vehicle (e.g. 1 for a typical autopilot).
public byte SystemId { get; }
Property Value
VehicleType
Vehicle category from the latest HEARTBEAT (quadrotor, plane, …).
public MavType VehicleType { get; protected set; }
Property Value
- MavType
Vel
Ground speed in m/s, updated from VFR_HUD.
public double Vel { get; }
Property Value
Methods
ArmAsync(CancellationToken)
Arms the vehicle. Resolves Confirmed once the armed bit is set in HEARTBEAT.
public Task<CommandOutcome> ArmAsync(CancellationToken ct = default)
Parameters
Returns
ClearFenceAsync(CancellationToken)
Clear the on-vehicle geofence plan.
public Task<MissionClearResult> ClearFenceAsync(CancellationToken ct = default)
Parameters
Returns
ClearMissionAsync(CancellationToken)
Clear the on-vehicle waypoint plan.
public Task<MissionClearResult> ClearMissionAsync(CancellationToken ct = default)
Parameters
Returns
ClearRallyAsync(CancellationToken)
Clear the on-vehicle rally-point plan.
public Task<MissionClearResult> ClearRallyAsync(CancellationToken ct = default)
Parameters
Returns
DisarmAsync(CancellationToken)
Disarms the vehicle. Resolves Confirmed once the armed bit is cleared in HEARTBEAT.
public Task<CommandOutcome> DisarmAsync(CancellationToken ct = default)
Parameters
Returns
DisposeAsync()
Performs application-defined tasks associated with freeing, releasing, or resetting unmanaged resources asynchronously.
public virtual ValueTask DisposeAsync()
Returns
- ValueTask
A task that represents the asynchronous dispose operation.
DownloadFenceAsync(CancellationToken)
Download the on-vehicle geofence plan.
public Task<MissionDownloadResult> DownloadFenceAsync(CancellationToken ct = default)
Parameters
Returns
DownloadMissionAsync(CancellationToken)
Download the on-vehicle waypoint plan.
public Task<MissionDownloadResult> DownloadMissionAsync(CancellationToken ct = default)
Parameters
Returns
DownloadRallyAsync(CancellationToken)
Download the on-vehicle rally-point plan.
public Task<MissionDownloadResult> DownloadRallyAsync(CancellationToken ct = default)
Parameters
Returns
LandAsync(CancellationToken)
Commands landing at the current position.
public virtual Task<CommandOutcome> LandAsync(CancellationToken ct = default)
Parameters
Returns
ReturnToLaunchAsync(CancellationToken)
Commands return-to-launch. Resolves Confirmed once mode switches to AUTO.RTL.
public Task<CommandOutcome> ReturnToLaunchAsync(CancellationToken ct = default)
Parameters
Returns
Send<T>(T)
Send an arbitrary message through this Vehicle's underlying connection. Useful for custom commands that don't have a typed wrapper.
protected void Send<T>(T message) where T : IMavlinkMessage<T>
Parameters
messageT
Type Parameters
T
SetCurrentMissionItemAsync(int, CancellationToken)
Set the current mission item by sequence number using
MAV_CMD_DO_SET_MISSION_CURRENT. The vehicle broadcasts an updated
MISSION_CURRENT on success, which is surfaced via
MissionCurrentSeq on the Vehicle. The COMMAND_LONG path resolves on ACK.
public Task<CommandOutcome> SetCurrentMissionItemAsync(int seq, CancellationToken ct = default)
Parameters
seqintctCancellationToken
Returns
Exceptions
- ArgumentOutOfRangeException
If
seqis outside[0, ushort.MaxValue].
StartMissionAsync(int, int, CancellationToken)
Begin executing the on-vehicle mission via
MAV_CMD_MISSION_START. Resolves Confirmed
when the vehicle reports AUTO.MISSION in HEARTBEAT.
<p>The vehicle must already have a mission uploaded (see
<xref href="MavNet.PX4.Base.Vehicle.UploadMissionAsync(System.Collections.Generic.IReadOnlyList%7bMavNet.PX4.Missions.MissionItem%7d%2cSystem.Threading.CancellationToken)" data-throw-if-not-resolved="false"></xref>) and typically must be armed.</p><p><code class="paramref">firstItem</code> and <code class="paramref">lastItem</code> select the
sub-range to run; defaults run the whole mission (<code>0</code> through <code>-1</code>
per spec).</p>
public Task<CommandOutcome> StartMissionAsync(int firstItem = 0, int lastItem = -1, CancellationToken ct = default)
Parameters
firstItemintlastItemintctCancellationToken
Returns
Exceptions
- ArgumentOutOfRangeException
If
firstItemorlastItemare outside[0, ushort.MaxValue](-1is allowed forlastItemand means "to the end").
SubscribeState(Action, StateRate)
Subscribe to state-change notifications at the given rate. The handler may run on
any thread — for Blazor consumers, marshal to the UI thread via InvokeAsync
inside the handler.
public StateSubscription SubscribeState(Action handler, StateRate rate)
Parameters
handlerActionCalled on each delivery. Exceptions are swallowed to keep the throttler alive.
rateStateRateRaw = every packet; otherwise rate-limited.
Returns
- StateSubscription
Dispose to unsubscribe. Idempotent.
TakeoffAsync(double, CancellationToken)
Commands takeoff to altMeters metres above the home point.
public virtual Task<CommandOutcome> TakeoffAsync(double altMeters, CancellationToken ct = default)
Parameters
altMetersdoublectCancellationToken
Returns
UploadFenceAsync(IReadOnlyList<MissionItem>, CancellationToken)
Upload the on-vehicle geofence plan.
public Task<MissionUploadResult> UploadFenceAsync(IReadOnlyList<MissionItem> items, CancellationToken ct = default)
Parameters
itemsIReadOnlyList<MissionItem>ctCancellationToken
Returns
UploadMissionAsync(IReadOnlyList<MissionItem>, CancellationToken)
Upload items as the on-vehicle waypoint plan. See
UploadAsync(IReadOnlyList<MissionItem>, CancellationToken) for timing, retry, and cancellation semantics.
public Task<MissionUploadResult> UploadMissionAsync(IReadOnlyList<MissionItem> items, CancellationToken ct = default)
Parameters
itemsIReadOnlyList<MissionItem>ctCancellationToken
Returns
UploadRallyAsync(IReadOnlyList<MissionItem>, CancellationToken)
Upload the on-vehicle rally-point plan.
public Task<MissionUploadResult> UploadRallyAsync(IReadOnlyList<MissionItem> items, CancellationToken ct = default)
Parameters
itemsIReadOnlyList<MissionItem>ctCancellationToken
Returns
Events
HeartbeatReceived
Diagnostic: fires once per inbound HEARTBEAT with the decoded payload and wall-clock receive timestamp.
public event Action<Heartbeat, DateTime>? HeartbeatReceived
Event Type
MissionItemReached
Fires once per inbound MISSION_ITEM_REACHED with the reached seq.
Useful for surfacing per-waypoint progress to the UI; MissionReachedCount
tracks the cumulative count.
public event Action<int>? MissionItemReached
Event Type
StateChanged
Fires after every state-affecting message — high frequency (10–50 Hz typical). Prefer
SubscribeState(Action, StateRate): it lets you pick a throttle rate at
the call site (StateRate.Hz(2), StateRate.Every(...), or StateRate.Raw
for full fidelity). This raw event remains public for consumers that genuinely want
every packet without going through the throttler.
public event Action? StateChanged