Skip to main content

MavlinkDrone

Inherits from: AerialDrone No class docstring.

Inherited methods

  • From Robot: addSensor, getImage, cleanup

init

MavlinkDrone.__init__(config_file: Optional[str] = None, ground_control_station_ip: Optional[str] = None, mavlink_port: Optional[str] = None, vehicle_ip: Optional[str] = None, communication_protocol: Optional[str] = None, camera_streams: Optional[Dict[str, Dict[str, Any]]] = None, arm_enable: Optional[bool] = None, dry_run: Optional[bool] = None, offboard_control_mode_int: Optional[int] = None, velocity_limit: float = 1.0, messages_known: Optional[List[str]] = None, messages_required: Optional[List[str]] = None)
Instantiates a MavlinkDrone containing a MavlinkClient for sending commands to the real drone. Additionally sets up a video stream manager for handling RTSP streams from the drone. If a config file is provided (a JSON file), then any parameters not explicitly provided (i.e. left as None) will be loaded from the config file (or fallback to the client’s own defaults). Otherwise, default values are used.
Arguments
config_file (Optional[str])
Optional[str]
Path to a JSON config file with parameter overrides.
ground_control_station_ip (Optional[str])
Optional[str]
IP address of the ground control station. (default: “192.168.8.10”)
Port number for the MAVLink connection. (default: “14550”)
vehicle_ip (Optional[str])
Optional[str]
IP address of the vehicle. (default: “192.168.8.1”)
communication_protocol (Optional[str])
Optional[str]
Communication protocol, one of (“udp”|“tcp”). (default: “udp”)
camera_streams (Optional[Dict[str, Dict[str, Any]]])
Optional[Dict[str, Dict[str, Any]]]
Dictionary mapping camera stream names to configuration.
arm_enable (Optional[bool])
Optional[bool]
Whether to enable arming the drone. (default: False)
dry_run (Optional[bool])
Optional[bool]
Whether to run in dry run mode bypassing arming exceptions. (default: False)
offboard_control_mode_int (Optional[int])
Optional[int]
No description provided.
velocity_limit (float)
float
Maximum velocity limit for the drone in m/s. (default: 1.0)
messages_known (Optional[List[str]])
Optional[List[str]]
No description provided.
messages_required (Optional[List[str]])
Optional[List[str]]
No description provided.

getPosition

MavlinkDrone.getPosition() -> Position
Get the current position of the drone with respect to the world coordinate.
Returns
Position
Position
Position type which internally contains X, Y, Z position in meters with respect to the world coordinate

getVelocity

MavlinkDrone.getVelocity() -> Velocity
Get the current velocity of the drone with respect to the world coordinate.
Returns
Velocity
Velocity
Velocity type which internally contains VX, VY, VZ velocity in meters/s

getYaw

MavlinkDrone.getYaw() -> float
Return the current yaw of the drone in radians. Yaw measures the rotation of the drone around the z axis of the aeronautical frame (right-handed, X front, Y right, Z down)
Returns
float
float
yaw of the drone in radians [-pi, +pi]

getOrientation

MavlinkDrone.getOrientation() -> Orientation
Return the current Orientation of the drone, these are internally stored as a quaternion (x, y, z, w) where w is the scalar component. These can be mapped to the euler angles in the aeronautical frame (right-handed, X front, Y right, Z down).
Returns
Orientation
Orientation
Current orientation of the drone in Orientation type

setYaw

MavlinkDrone.setYaw(yaw: float) -> None
Set the yaw (in radians) of the drone to the specified position. Yaw measures the rotation of the drone around the z-axis (downwards). The yaw is wrapped to stay within [-pi, pi].
Arguments
yaw (float)
float
required
the target yaw (radians) for the drone
Returns
returns
None

setYawDelta

MavlinkDrone.setYawDelta(yaw_delta: float) -> None
Set a yaw delta (in radians) for the drone to rotate to. Yaw measures the rotation of the drone around the z-axis (downwards). The resulting yaw will be wrapped to stay within [-pi, pi].
Arguments
yaw_delta (float)
float
required
the change in yaw (radians) for the drone
Returns
returns
None

setYawRate

MavlinkDrone.setYawRate(yaw_rate: float) -> None
Set the yaw rate of the drone in radians/s. Yaw measures the rotation of the drone around the z-axis (downwards)
Arguments
yaw_rate (float)
float
required
the target yaw_rate (radians/s) for the drone
Returns
returns
None

moveToPosition

MavlinkDrone.moveToPosition(position: Position, no_sideslip: bool = False) -> None
Move the drone to position: (x_val, y_val, z_val) respect to the world coordinates in NED frame (right handed, z down). If no_sideslip is specified drone turns in direction of travel. Velocity is limited to be less than velocity limit value.
Arguments
position (Position)
Position
required
contains x, y, and z position in meters in NED frame
no_sideslip (bool)
bool
whether to turn in direction of travel (default: False)
Returns
returns
None

moveToPositionDelta

MavlinkDrone.moveToPositionDelta(position_delta: Position, no_sideslip: bool = False) -> None
Move the drone by position_delta: (x_val, y_val, z_val) relative to the current location with respect to the world coordinates in NED frame (right handed, z down). If no_sideslip is specified drone turns in direction of travel. Velocity is limited to be less than velocity limit value.
Arguments
position_delta (Position)
Position
required
contains x, y, and z position deltas in meters in NED frame
no_sideslip (bool)
bool
whether to turn in direction of travel (default: False)
Returns
returns
None

moveToGPS

MavlinkDrone.moveToGPS(lat: float, lon: float, alt: float, alt_use_msl: bool = False) -> None
Move the drone to GPS coordinate: (lat, lon, alt) with respect to world coordinates in WGS84 frame (right handed, z up). By default altitude is relative to starting point, can be set to absolute MSL using alt_use_msl. Note that NO velocity limiting is applied beyond PX4 limitation; drone moves using internal position tracking.
Arguments
lat (float)
float
required
target latitude in degrees
lon (float)
float
required
target longitude in degrees
alt (float)
float
required
target altitude in meters
alt_use_msl (bool)
bool
flag to use altitude in absolute meters above sea level (MSL) (default: False)
Returns
returns
None

moveByVelocity

MavlinkDrone.moveByVelocity(velocity: Velocity, duration: float = None, no_sideslip: bool = False) -> None
Fly the drone with velocity in NED frame (right-handed, X north, Y east, Z down) in meters/s. If an optional duration is given, the velocity command is held for the specified number of seconds during which the function is blocking. After the duration is complete the final position is held. If no duration is specified (default), the command is held until another position or velocity command is given. If no_sideslip is specified drone turns in direction of travel. Velocity is limited to be less than velocity limit value.
Arguments
velocity (Velocity)
Velocity
required
contains x velocity (x_vel), y velocity (y_vel), z velocity (z_vel)
duration (float)
float
number of seconds that the drone should move before stopping, holds final position
no_sideslip (bool)
bool
whether to turn in direction of travel (default: False)
Returns
returns
None

takeoff

MavlinkDrone.takeoff() -> None
Takeoff the ModalAI drone. Starts by arming the drone. Holds final position after takeoff.
Returns
returns
None

land

MavlinkDrone.land() -> None
Land the ModalAI drone. Descends at 1m/s until reaching 2m altitude. Final descent is at 0.25m/s until 0.1m altitude, then sets 0.5m/s velocity down for 2s to ensure touchdown before disarming the drone. NOTE: altitude values are given relative to starting location.
Returns
returns
None

getState

MavlinkDrone.getState()
Get the current state of the drone, including position, velocity, and orientation.

stop

MavlinkDrone.stop() -> None
Stop the drone. Immediately sets velocity to zero.
Returns
returns
None