pub struct STORM32_GIMBAL_MANAGER_CONTROL_DATA {
pub q: [f32; 4],
pub angular_velocity_x: f32,
pub angular_velocity_y: f32,
pub angular_velocity_z: f32,
pub device_flags: GimbalDeviceFlags,
pub manager_flags: MavStorm32GimbalManagerFlags,
pub target_system: u8,
pub target_component: u8,
pub gimbal_id: u8,
pub client: MavStorm32GimbalManagerClient,
}
storm32
only.Expand description
id: 60012 Message to a gimbal manager to control the gimbal attitude. Angles and rates can be set to NaN according to use case. A gimbal device is never to react to this message.
Fields§
§q: [f32; 4]
Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation). Set first element to NaN to be ignored. The frame is determined by the GIMBAL_DEVICE_FLAGS_YAW_IN_xxx_FRAME flags.
angular_velocity_x: f32
X component of angular velocity (positive: roll to the right). NaN to be ignored.
angular_velocity_y: f32
Y component of angular velocity (positive: tilt up). NaN to be ignored.
angular_velocity_z: f32
Z component of angular velocity (positive: pan to the right). NaN to be ignored. The frame is determined by the GIMBAL_DEVICE_FLAGS_YAW_IN_xxx_FRAME flags.
device_flags: GimbalDeviceFlags
Gimbal device flags to be applied (UINT16_MAX to be ignored). Same flags as used in GIMBAL_DEVICE_SET_ATTITUDE.
manager_flags: MavStorm32GimbalManagerFlags
Gimbal manager flags to be applied (0 to be ignored).
target_system: u8
System ID
target_component: u8
Component ID
gimbal_id: u8
Gimbal ID of the gimbal manager to address (component ID or 1-6 for non-MAVLink gimbal, 0 for all gimbals). Send command multiple times for more than one but not all gimbals.
client: MavStorm32GimbalManagerClient
Client which is contacting the gimbal manager (must be set).
Implementations§
Source§impl STORM32_GIMBAL_MANAGER_CONTROL_DATA
impl STORM32_GIMBAL_MANAGER_CONTROL_DATA
pub const ENCODED_LEN: usize = 36usize
pub const DEFAULT: Self
Trait Implementations§
Source§impl Clone for STORM32_GIMBAL_MANAGER_CONTROL_DATA
impl Clone for STORM32_GIMBAL_MANAGER_CONTROL_DATA
Source§fn clone(&self) -> STORM32_GIMBAL_MANAGER_CONTROL_DATA
fn clone(&self) -> STORM32_GIMBAL_MANAGER_CONTROL_DATA
1.0.0 · Source§fn clone_from(&mut self, source: &Self)
fn clone_from(&mut self, source: &Self)
source
. Read moreSource§impl<'de> Deserialize<'de> for STORM32_GIMBAL_MANAGER_CONTROL_DATA
impl<'de> Deserialize<'de> for STORM32_GIMBAL_MANAGER_CONTROL_DATA
Source§fn deserialize<__D>(__deserializer: __D) -> Result<Self, __D::Error>where
__D: Deserializer<'de>,
fn deserialize<__D>(__deserializer: __D) -> Result<Self, __D::Error>where
__D: Deserializer<'de>,
Source§impl MessageData for STORM32_GIMBAL_MANAGER_CONTROL_DATA
impl MessageData for STORM32_GIMBAL_MANAGER_CONTROL_DATA
const ID: u32 = 60_012u32
const NAME: &'static str = "STORM32_GIMBAL_MANAGER_CONTROL"
const EXTRA_CRC: u8 = 99u8
const ENCODED_LEN: usize = 36usize
type Message = MavMessage
fn deser(_version: MavlinkVersion, __input: &[u8]) -> Result<Self, ParserError>
fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize
Source§impl PartialEq for STORM32_GIMBAL_MANAGER_CONTROL_DATA
impl PartialEq for STORM32_GIMBAL_MANAGER_CONTROL_DATA
Source§fn eq(&self, other: &STORM32_GIMBAL_MANAGER_CONTROL_DATA) -> bool
fn eq(&self, other: &STORM32_GIMBAL_MANAGER_CONTROL_DATA) -> bool
self
and other
values to be equal, and is used by ==
.