Mocap¶
-
class
mavsdk.mocap.
AngleBody
(roll_rad, pitch_rad, yaw_rad)¶ Bases:
object
Body angle type
- Parameters
roll_rad (float) – Roll angle in radians.
pitch_rad (float) – Pitch angle in radians.
yaw_rad (float) – Yaw angle in radians.
-
class
mavsdk.mocap.
AngularVelocityBody
(roll_rad_s, pitch_rad_s, yaw_rad_s)¶ Bases:
object
Angular velocity type
- Parameters
roll_rad_s (float) – Roll angular velocity in radians/second.
pitch_rad_s (float) – Pitch angular velocity in radians/second.
yaw_rad_s (float) – Yaw angular velocity in radians/second.
-
class
mavsdk.mocap.
AttitudePositionMocap
(time_usec, q, position_body, pose_covariance)¶ Bases:
object
Motion capture attitude and position
- Parameters
time_usec (uint64_t) – PositionBody frame timestamp UNIX Epoch time (0 to use Backend timestamp)
q (Quaternion) – Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)
position_body (PositionBody) – Body Position (NED)
pose_covariance (Covariance) – Pose cross-covariance matrix.
-
class
mavsdk.mocap.
Covariance
(covariance_matrix)¶ Bases:
object
Covariance type. Row-major representation of a 6x6 cross-covariance matrix upper right triangle. Needs to be 21 entries or 1 entry with NaN if unknown.
- Parameters
covariance_matrix ([float]) – The covariance matrix
-
class
mavsdk.mocap.
Mocap
(async_plugin_manager)¶ Bases:
mavsdk._base.AsyncBase
Allows interfacing a vehicle with a motion capture system in order to allow navigation without global positioning sources available (e.g. indoors, or when flying under a bridge. etc.).
Generated by dcsdkgen - MAVSDK Mocap API
-
name
= 'Mocap'¶
-
async
set_attitude_position_mocap
(attitude_position_mocap)¶ Send motion capture attitude and position.
- Parameters
attitude_position_mocap (AttitudePositionMocap) – The attitude and position data
- Raises
MocapError – If the request fails. The error contains the reason for the failure.
-
async
set_odometry
(odometry)¶ Send odometry information with an external interface.
- Parameters
odometry (Odometry) – The odometry data
- Raises
MocapError – If the request fails. The error contains the reason for the failure.
-
async
set_vision_position_estimate
(vision_position_estimate)¶ Send Global position/attitude estimate from a vision source.
- Parameters
vision_position_estimate (VisionPositionEstimate) – The vision position estimate
- Raises
MocapError – If the request fails. The error contains the reason for the failure.
-
-
exception
mavsdk.mocap.
MocapError
(result, origin, *params)¶ Bases:
Exception
Raised when a MocapResult is a fail code
-
class
mavsdk.mocap.
MocapResult
(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.Enum
Possible results returned for mocap requests
- UNKNOWN
Unknown error
- SUCCESS
Request succeeded
- NO_SYSTEM
No system is connected
- CONNECTION_ERROR
Connection error
- INVALID_REQUEST_DATA
Invalid request data
-
CONNECTION_ERROR
= 3¶
-
INVALID_REQUEST_DATA
= 4¶
-
NO_SYSTEM
= 2¶
-
SUCCESS
= 1¶
-
UNKNOWN
= 0¶
-
class
mavsdk.mocap.
Odometry
(time_usec, frame_id, position_body, q, speed_body, angular_velocity_body, pose_covariance, velocity_covariance)¶ Bases:
object
Odometry message to communicate odometry information with an external interface.
- Parameters
time_usec (uint64_t) – Timestamp (0 to use Backend timestamp).
frame_id (MavFrame) – Coordinate frame of reference for the pose data.
position_body (PositionBody) – Body Position.
q (Quaternion) – Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation).
speed_body (SpeedBody) – Linear speed (m/s).
angular_velocity_body (AngularVelocityBody) – Angular speed (rad/s).
pose_covariance (Covariance) – Pose cross-covariance matrix.
velocity_covariance (Covariance) – Velocity cross-covariance matrix.
-
class
MavFrame
(value)¶ Bases:
enum.Enum
Mavlink frame id
- MOCAP_NED
MAVLink number: 14. Odometry local coordinate frame of data given by a motion capture system, Z-down (x: north, y: east, z: down).
- LOCAL_FRD
MAVLink number: 20. Forward, Right, Down coordinate frame. This is a local frame with Z-down and arbitrary F/R alignment (i.e. not aligned with NED/earth frame). Replacement for MAV_FRAME_MOCAP_NED, MAV_FRAME_VISION_NED, MAV_FRAME_ESTIM_NED.
-
LOCAL_FRD
= 1¶
-
MOCAP_NED
= 0¶
-
class
mavsdk.mocap.
PositionBody
(x_m, y_m, z_m)¶ Bases:
object
Body position type
- Parameters
x_m (float) – X position in metres.
y_m (float) – Y position in metres.
z_m (float) – Z position in metres.
-
class
mavsdk.mocap.
Quaternion
(w, x, y, z)¶ Bases:
object
Quaternion type.
All rotations and axis systems follow the right-hand rule. The Hamilton quaternion product definition is used. A zero-rotation quaternion is represented by (1,0,0,0). The quaternion could also be written as w + xi + yj + zk.
For more info see: https://en.wikipedia.org/wiki/Quaternion
- Parameters
w (float) – Quaternion entry 0, also denoted as a
x (float) – Quaternion entry 1, also denoted as b
y (float) – Quaternion entry 2, also denoted as c
z (float) – Quaternion entry 3, also denoted as d
-
class
mavsdk.mocap.
SpeedBody
(x_m_s, y_m_s, z_m_s)¶ Bases:
object
Speed type, represented in the Body (X Y Z) frame and in metres/second.
- Parameters
x_m_s (float) – Velocity in X in metres/second.
y_m_s (float) – Velocity in Y in metres/second.
z_m_s (float) – Velocity in Z in metres/second.
-
class
mavsdk.mocap.
VisionPositionEstimate
(time_usec, position_body, angle_body, pose_covariance)¶ Bases:
object
Global position/attitude estimate from a vision source.
- Parameters
time_usec (uint64_t) – PositionBody frame timestamp UNIX Epoch time (0 to use Backend timestamp)
position_body (PositionBody) – Global position (m)
angle_body (AngleBody) – Body angle (rad).
pose_covariance (Covariance) – Pose cross-covariance matrix.