LandingTarget class
The location of a landing target. See: https://mavlink.io/en/services/landing_target.html
LANDING_TARGET
- Implemented types
Constructors
-
LandingTarget({required uint64_t timeUsec, required float angleX, required float angleY, required float distance, required float sizeX, required float sizeY, required uint8_t targetNum, required MavFrame frame, required float x, required float y, required float z, required List<
float> q, required LandingTargetType type, required uint8_t positionValid}) - LandingTarget.parse(ByteData data_)
-
factory
Properties
- angleX → float
-
X-axis angular offset of the target from the center of the image
final
- angleY → float
-
Y-axis angular offset of the target from the center of the image
final
- distance → float
-
Distance to the target from the vehicle
final
- frame → MavFrame
-
Coordinate frame used for following fields.
final
- hashCode → int
-
The hash code for this object.
no setterinherited
- mavlinkCrcExtra → int
-
no setteroverride
- mavlinkMessageId → int
-
no setteroverride
- positionValid → uint8_t
-
Boolean indicating whether the position fields (x, y, z, q, type) contain valid target position information (valid: 1, invalid: 0). Default is 0 (invalid).
final
-
q
→ List<
float> -
Quaternion of landing target orientation (w, x, y, z order, zero-rotation is 1, 0, 0, 0)
final
- runtimeType → Type
-
A representation of the runtime type of the object.
no setterinherited
- sizeX → float
-
Size of target along x-axis
final
- sizeY → float
-
Size of target along y-axis
final
- targetNum → uint8_t
-
The ID of the target if multiple targets are present
final
- timeUsec → uint64_t
-
Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
final
- type → LandingTargetType
-
Type of landing target
final
- x → float
-
X Position of the landing target in MAV_FRAME
final
- y → float
-
Y Position of the landing target in MAV_FRAME
final
- z → float
-
Z Position of the landing target in MAV_FRAME
final
Methods
-
noSuchMethod(
Invocation invocation) → dynamic -
Invoked when a nonexistent method or property is accessed.
inherited
-
serialize(
) → ByteData -
override
-
toString(
) → String -
A string representation of this object.
inherited
Operators
-
operator ==(
Object other) → bool -
The equality operator.
inherited
Constants
- mavlinkEncodedLength → const int