[][src]Struct mavlink::common::GIMBAL_DEVICE_SET_ATTITUDE_DATA

pub struct GIMBAL_DEVICE_SET_ATTITUDE_DATA {
    pub q: [f32; 4],
    pub angular_velocity_x: f32,
    pub angular_velocity_y: f32,
    pub angular_velocity_z: f32,
    pub flags: GimbalDeviceFlags,
    pub target_system: u8,
    pub target_component: u8,
}

id: 284 Low level message to control a gimbal device's attitude. This message is to be sent from the gimbal manager to the gimbal device component. Angles and rates can be set to NaN according to use case..

Fields

q: [f32; 4]

Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation, the frame is depends on whether the flag GIMBAL_DEVICE_FLAGS_YAW_LOCK is set, set all fields to NaN if only angular velocity should be used).

angular_velocity_x: f32

X component of angular velocity, positive is banking to the right, NaN to be ignored..

angular_velocity_y: f32

Y component of angular velocity, positive is tilting up, NaN to be ignored..

angular_velocity_z: f32

Z component of angular velocity, positive is panning to the right, NaN to be ignored..

flags: GimbalDeviceFlags

Low level gimbal flags..

target_system: u8

System ID.

target_component: u8

Component ID.

Implementations

impl GIMBAL_DEVICE_SET_ATTITUDE_DATA[src]

pub const ENCODED_LEN: usize[src]

pub fn deser(
    version: MavlinkVersion,
    _input: &[u8]
) -> Result<Self, ParserError>
[src]

pub fn ser(&self) -> Vec<u8>[src]

Trait Implementations

impl Clone for GIMBAL_DEVICE_SET_ATTITUDE_DATA[src]

impl Debug for GIMBAL_DEVICE_SET_ATTITUDE_DATA[src]

impl Default for GIMBAL_DEVICE_SET_ATTITUDE_DATA[src]

impl<'de> Deserialize<'de> for GIMBAL_DEVICE_SET_ATTITUDE_DATA[src]

impl PartialEq<GIMBAL_DEVICE_SET_ATTITUDE_DATA> for GIMBAL_DEVICE_SET_ATTITUDE_DATA[src]

impl Serialize for GIMBAL_DEVICE_SET_ATTITUDE_DATA[src]

impl StructuralPartialEq for GIMBAL_DEVICE_SET_ATTITUDE_DATA[src]

Auto Trait Implementations

Blanket Implementations

impl<T> Any for T where
    T: 'static + ?Sized
[src]

impl<T> Borrow<T> for T where
    T: ?Sized
[src]

impl<T> BorrowMut<T> for T where
    T: ?Sized
[src]

impl<T> DeserializeOwned for T where
    T: for<'de> Deserialize<'de>, 
[src]

impl<T> From<T> for T[src]

impl<T, U> Into<U> for T where
    U: From<T>, 
[src]

impl<T> ToOwned for T where
    T: Clone
[src]

type Owned = T

The resulting type after obtaining ownership.

impl<T, U> TryFrom<U> for T where
    U: Into<T>, 
[src]

type Error = Infallible

The type returned in the event of a conversion error.

impl<T, U> TryInto<U> for T where
    U: TryFrom<T>, 
[src]

type Error = <U as TryFrom<T>>::Error

The type returned in the event of a conversion error.