ManualControl class
This message provides an API for manually controlling the vehicle using standard joystick axes nomenclature, along with a joystick-like input device. Unused axes can be disabled and buttons states are transmitted as individual on/off bits of a bitmask
MANUAL_CONTROL
- Implemented types
Constructors
- ManualControl({required int16_t x, required int16_t y, required int16_t z, required int16_t r, required uint16_t buttons, required uint8_t target, required uint16_t buttons2, required uint8_t enabledExtensions, required int16_t s, required int16_t t, required int16_t aux1, required int16_t aux2, required int16_t aux3, required int16_t aux4, required int16_t aux5, required int16_t aux6})
- ManualControl.parse(ByteData data_)
-
factory
Properties
- aux1 → int16_t
-
Aux continuous input field 1. Normalized in the range
-1000,1000
. Purpose defined by recipient. Valid data if bit 2 of enabled_extensions field is set. 0 if bit 2 is unset.final - aux2 → int16_t
-
Aux continuous input field 2. Normalized in the range
-1000,1000
. Purpose defined by recipient. Valid data if bit 3 of enabled_extensions field is set. 0 if bit 3 is unset.final - aux3 → int16_t
-
Aux continuous input field 3. Normalized in the range
-1000,1000
. Purpose defined by recipient. Valid data if bit 4 of enabled_extensions field is set. 0 if bit 4 is unset.final - aux4 → int16_t
-
Aux continuous input field 4. Normalized in the range
-1000,1000
. Purpose defined by recipient. Valid data if bit 5 of enabled_extensions field is set. 0 if bit 5 is unset.final - aux5 → int16_t
-
Aux continuous input field 5. Normalized in the range
-1000,1000
. Purpose defined by recipient. Valid data if bit 6 of enabled_extensions field is set. 0 if bit 6 is unset.final - aux6 → int16_t
-
Aux continuous input field 6. Normalized in the range
-1000,1000
. Purpose defined by recipient. Valid data if bit 7 of enabled_extensions field is set. 0 if bit 7 is unset.final -
A bitfield corresponding to the joystick buttons' 0-15 current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1.
final
-
A bitfield corresponding to the joystick buttons' 16-31 current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 16.
final
- enabledExtensions → uint8_t
-
Set bits to 1 to indicate which of the following extension fields contain valid data: bit 0: pitch, bit 1: roll, bit 2: aux1, bit 3: aux2, bit 4: aux3, bit 5: aux4, bit 6: aux5, bit 7: aux6
final
- hashCode → int
-
The hash code for this object.
no setterinherited
- mavlinkCrcExtra → int
-
no setteroverride
- mavlinkMessageId → int
-
no setteroverride
- r → int16_t
-
R-axis, normalized to the range
-1000,1000
. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle.final - runtimeType → Type
-
A representation of the runtime type of the object.
no setterinherited
- s → int16_t
-
Pitch-only-axis, normalized to the range
-1000,1000
. Generally corresponds to pitch on vehicles with additional degrees of freedom. Valid if bit 0 of enabled_extensions field is set. Set to 0 if invalid.final - t → int16_t
-
Roll-only-axis, normalized to the range
-1000,1000
. Generally corresponds to roll on vehicles with additional degrees of freedom. Valid if bit 1 of enabled_extensions field is set. Set to 0 if invalid.final - target → uint8_t
-
The system to be controlled.
final
- x → int16_t
-
X-axis, normalized to the range
-1000,1000
. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle.final - y → int16_t
-
Y-axis, normalized to the range
-1000,1000
. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle.final - z → int16_t
-
Z-axis, normalized to the range
-1000,1000
. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle. Positive values are positive thrust, negative values are negative thrust.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