Struct MissionItem
Protocol-shaped mission item — mirrors the MAVLink MISSION_ITEM_INT wire
layout but without the per-transaction fields (Seq, TargetSystem,
TargetComponent, MissionType). MissionClient stamps
those in when it sends each item.
Coordinate scaling matches the spec: for global frames, X /
Y are degrees × 1e7; for local frames, metres × 1e4.
Z is always a float. Use the static factories
(Waypoint, Takeoff, Land, ReturnToLaunch) to avoid hand-scaling.
The same record is used for waypoint, geofence, and rally-point missions
— the Command field plus MAV_MISSION_TYPE (passed to the
MissionClient) determine the semantics.
public readonly record struct MissionItem : IEquatable<MissionItem>
- Implements
- Inherited Members
Constructors
MissionItem(MavFrame, MavCmd, float, float, float, float, int, int, float, byte)
Protocol-shaped mission item — mirrors the MAVLink MISSION_ITEM_INT wire
layout but without the per-transaction fields (Seq, TargetSystem,
TargetComponent, MissionType). MissionClient stamps
those in when it sends each item.
Coordinate scaling matches the spec: for global frames, X /
Y are degrees × 1e7; for local frames, metres × 1e4.
Z is always a float. Use the static factories
(Waypoint, Takeoff, Land, ReturnToLaunch) to avoid hand-scaling.
The same record is used for waypoint, geofence, and rally-point missions
— the Command field plus MAV_MISSION_TYPE (passed to the
MissionClient) determine the semantics.
public MissionItem(MavFrame Frame, MavCmd Command, float Param1, float Param2, float Param3, float Param4, int X, int Y, float Z, byte AutoContinue = 1)
Parameters
FrameMavFrameCommandMavCmdParam1floatParam2floatParam3floatParam4floatXintYintZfloatAutoContinuebyte
Properties
AutoContinue
public byte AutoContinue { get; init; }
Property Value
Command
public MavCmd Command { get; init; }
Property Value
- MavCmd
Frame
public MavFrame Frame { get; init; }
Property Value
- MavFrame
Param1
public float Param1 { get; init; }
Property Value
Param2
public float Param2 { get; init; }
Property Value
Param3
public float Param3 { get; init; }
Property Value
Param4
public float Param4 { get; init; }
Property Value
X
public int X { get; init; }
Property Value
Y
public int Y { get; init; }
Property Value
Z
public float Z { get; init; }
Property Value
Methods
FromInt1e7(int)
Decode MAVLink int32 (× 1e7) back to degrees.
public static double FromInt1e7(int scaled)
Parameters
scaledint
Returns
Land(double, double, float, MavFrame)
Build a NAV_LAND item at the given coordinate. abortAlt
is the minimum altitude (m) the autopilot may abort a landing at (param1).
public static MissionItem Land(double latDeg, double lonDeg, float abortAlt = 0, MavFrame frame = MavFrame.GlobalRelativeAltInt)
Parameters
Returns
ReturnToLaunch()
Build a NAV_RETURN_TO_LAUNCH item.
public static MissionItem ReturnToLaunch()
Returns
Takeoff(double, double, float, float, MavFrame)
Build a NAV_TAKEOFF item at an explicit coordinate
(latDeg, lonDeg, altMeters).
public static MissionItem Takeoff(double latDeg, double lonDeg, float altMeters, float pitch = 0, MavFrame frame = MavFrame.GlobalRelativeAltInt)
Parameters
Returns
Takeoff(float, float, MavFrame)
Build a NAV_TAKEOFF item with X/Y emitted as
0 and Z = altMeters. Per the
MISSION_ITEM_INT encoding 0 is the literal coordinate 0.0000000°,
not an "unset"/"current position" sentinel — the protocol has no unset. Use
Takeoff(double, double, float, float, MavFrame) to send a takeoff
coordinate.
public static MissionItem Takeoff(float altMeters, float pitch = 0, MavFrame frame = MavFrame.GlobalRelativeAltInt)
Parameters
Returns
ToInt1e7(double)
Encode degrees to MAVLink int32 (× 1e7), rounding half-away-from-zero.
public static int ToInt1e7(double degrees)
Parameters
degreesdouble
Returns
Waypoint(double, double, float, float, float, MavFrame)
Build a NAV_WAYPOINT item from human-friendly degrees/metres. hold
is the time-to-hold in seconds at the waypoint (param1); acceptanceRadius
is the radius (m) within which the waypoint is considered reached (param2).
public static MissionItem Waypoint(double latDeg, double lonDeg, float altMeters, float hold = 0, float acceptanceRadius = 0, MavFrame frame = MavFrame.GlobalRelativeAltInt)