Core Types¶
types
¶
Type definitions and enums for Drone API.
These enums replace magic numbers throughout the codebase with type-safe constants.
Direction
¶
Bases: IntEnum
Movement direction for move() command.
FORWARD/BACK map to MAVLink command ID 30 with +/- distance.
LEFT/RIGHT map to MAVLink command ID 31 with +/- distance.
UP/DOWN map to MAVLink command ID 32 with +/- height.
Rotation
¶
FlipDirection
¶
Bases: IntEnum
Direction for flip/somersault maneuver.
Maps to the direction parameter in single_fly_somersault().
LEDMode
¶
Bases: IntEnum
LED lighting mode.
Maps to the mode parameter in single_fly_lamplight().
DroneStatus
¶
Bases: IntEnum
Drone operational status from telemetry.
CommandResult
¶
Bases: IntEnum
Result code from command execution.
Based on MAVLink PLANE_ACK message result codes.
VisionMode
¶
AIRecognitionTarget
¶
Bases: IntEnum
Target types for AI recognition.
Used with single_fly_AiIdentifies() for recognizing visual markers.
CameraMode
¶
Bases: IntEnum
Camera angle control mode.
Used with Plane_cmd_camera_angle().
ClampMode
¶
Bases: IntEnum
Gripper/clamp control mode.
Used with MAV_PLANE_CMD_CLAMP_ELECTROMAGNET (cmd=26).
Type values:
- 0=CLOSE
- 1=OPEN
- 2=SET_ANGLE (with data=angle)
ElectromagnetMode
¶
VideoMode
¶
LineWalkingMode
¶
BarrierMode
¶
LineFollowResult
¶
LineColor
¶
LaserMode
¶
Bases: IntEnum
Laser firing mode.
Used with fire_laser() / plane_fly_generating().
CameraPitchMode
¶
Bases: IntEnum
Camera pitch control mode.
Used with set_camera_angle() / Plane_cmd_camera_angle().
Controls the main camera's vertical angle.
VideoStreamMode
¶
QRLocalizationMode
¶
MediaType
¶
Bases: IntEnum
Media type for file operations.
Used with list_media(), download_media(), delete_media().
Maps to the media_type/del_type parameters in the HTTP CGI API.
VelocityLevel
¶
Bases: IntEnum
Flight velocity level for position controller gain scaling.
Used with movement commands like move() and move_to() to control flight speed.
Pass as the speed parameter:
drone.move(Direction.FORWARD, 100, speed=VelocityLevel.ZOOM)
drone.move_to(x=100, y=100, z=50, speed=VelocityLevel.TURBO)
Firmware behavior:
The firmware uses this value as a DIVISOR for the position P-gain:
gain = MPC_XY_P (2.0) / cruising_speed
Higher values -> lower gain -> slower, gentler approach
Lower values -> higher gain -> faster, more aggressive approach
Note
set_velocity_level() only affects RC/joystick manual control, not API commands.
BarrierMask
¶
Bases: IntFlag
Obstacle sensor bitmask for set_avoidance_direction().
Specifies which IR/ToF sensors to check for obstacles.
Can be combined with | operator: BarrierMask.FRONT | BarrierMask.BACK
Maps to mav_barrier_info in firmware.
VideoResolution
¶
Bases: IntEnum
Video resolution level for RTP streaming and recording.
Used with set_video_resolution() to control video quality vs performance.
Lower resolution reduces encoder CPU load, which may allow higher QR localization rates when RTP streaming is active.
Firmware handler: HandleMsgSelectRecordResolution @ avmanager:0x0001df7c
Command: MAV_PLANE_CMD_SELECT_VIDEO_RESOLUTION (0x16)
Resolution affects:
- RTP streaming quality and bandwidth
- Video recording file size
- Encoder CPU load (lower = less load)
WiFiMode
¶
Bases: IntEnum
WiFi configuration mode.
Used with MAV_PLANE_CMD_WIFI_MODE (cmd=4). The type parameter selects the WiFi operation.
Firmware handler: HandleMsgWifiMode @ avmanager
TakeoffFlags
¶
Bases: IntFlag
Takeoff behavior flags (param2 in ONE_KEY_TAKEOFF command).
Controls special takeoff behaviors. Can be combined with | operator.
Firmware behavior (handle_formation_cmd_handler @ 0x00043424):
- Bit 0 (RESET_YAW): Resets yaw orientation on takeoff
- Bit 1 (WITH_LOAD): Enables "takeoff with load" mode for heavier payloads
C# reference (SingleGameProgrammingAdapter.cs):
- LaunchHeight (param2=0): Normal takeoff
- LaunchHeightWithClamp (param2=2): Takeoff with load clamp
Usage: