ManualControl¶
- class mavsdk.manual_control.ManualControl(async_plugin_manager)¶
Bases:
AsyncBase
Enable manual control using e.g. a joystick or gamepad.
Generated by dcsdkgen - MAVSDK ManualControl API
- name = 'ManualControl'¶
- async set_manual_control_input(x, y, z, r)¶
Set manual control input
The manual control input needs to be sent at a rate high enough to prevent triggering of RC loss, a good minimum rate is 10 Hz.
- Parameters:
x (float) – value between -1. to 1. negative -> backwards, positive -> forwards
y (float) – value between -1. to 1. negative -> left, positive -> right
z (float) – value between -1. to 1. negative -> down, positive -> up (usually for now, for multicopter 0 to 1 is expected)
r (float) – value between -1. to 1. negative -> turn anti-clockwise (towards the left), positive -> turn clockwise (towards the right)
- Raises:
ManualControlError – If the request fails. The error contains the reason for the failure.
- async start_altitude_control()¶
Start altitude control
Requires manual control input to be sent regularly already. Does not require a valid position e.g. GPS.
- Raises:
ManualControlError – If the request fails. The error contains the reason for the failure.
- async start_position_control()¶
Start position control using e.g. joystick input.
Requires manual control input to be sent regularly already. Requires a valid position using e.g. GPS, external vision, or optical flow.
- Raises:
ManualControlError – If the request fails. The error contains the reason for the failure.
- exception mavsdk.manual_control.ManualControlError(result, origin, *params)¶
Bases:
Exception
Raised when a ManualControlResult is a fail code
- class mavsdk.manual_control.ManualControlResult(result, result_str)¶
Bases:
object
Result type.
- Parameters:
result (Result) – Result enum value
result_str (std::string) – Human-readable English string describing the result
- class Result(value)¶
Bases:
Enum
Possible results returned for manual control requests.
Values¶
- UNKNOWN
Unknown result
- SUCCESS
Request was successful
- NO_SYSTEM
No system is connected
- CONNECTION_ERROR
Connection error
- BUSY
Vehicle is busy
- COMMAND_DENIED
Command refused by vehicle
- TIMEOUT
Request timed out
- INPUT_OUT_OF_RANGE
Input out of range
- INPUT_NOT_SET
No Input set
- BUSY = 4¶
- COMMAND_DENIED = 5¶
- CONNECTION_ERROR = 3¶
- INPUT_NOT_SET = 8¶
- INPUT_OUT_OF_RANGE = 7¶
- NO_SYSTEM = 2¶
- SUCCESS = 1¶
- TIMEOUT = 6¶
- UNKNOWN = 0¶