pub struct SimState {Show 23 fields
pub q1: f32,
pub q2: f32,
pub q3: f32,
pub q4: f32,
pub roll: f32,
pub pitch: f32,
pub yaw: f32,
pub xacc: f32,
pub yacc: f32,
pub zacc: f32,
pub xgyro: f32,
pub ygyro: f32,
pub zgyro: f32,
pub lat: f32,
pub lon: f32,
pub alt: f32,
pub std_dev_horz: f32,
pub std_dev_vert: f32,
pub vn: f32,
pub ve: f32,
pub vd: f32,
pub lat_int: i32,
pub lon_int: i32,
}Expand description
MAVLink SIM_STATE message.
The minimum supported MAVLink version is MAVLink 1.
§Description
Status of simulation environment, if used
§Encoding/Decoding
Message encoding/decoding are provided by implementing core::convert::TryFrom<Payload> for
SimState (encoding) and [IntoPayload] (decoding) traits.
These traits are implemented by Message proc macro.
Fields§
§q1: f32MAVLink field q1.
True attitude quaternion component 1, w (1 in null-rotation)
q2: f32MAVLink field q2.
True attitude quaternion component 2, x (0 in null-rotation)
q3: f32MAVLink field q3.
True attitude quaternion component 3, y (0 in null-rotation)
q4: f32MAVLink field q4.
True attitude quaternion component 4, z (0 in null-rotation)
roll: f32MAVLink field roll.
Attitude roll expressed as Euler angles, not recommended except for human-readable outputs
pitch: f32MAVLink field pitch.
Attitude pitch expressed as Euler angles, not recommended except for human-readable outputs
yaw: f32MAVLink field yaw.
Attitude yaw expressed as Euler angles, not recommended except for human-readable outputs
xacc: f32MAVLink field xacc.
X acceleration
yacc: f32MAVLink field yacc.
Y acceleration
zacc: f32MAVLink field zacc.
Z acceleration
xgyro: f32MAVLink field xgyro.
Angular speed around X axis
ygyro: f32MAVLink field ygyro.
Angular speed around Y axis
zgyro: f32MAVLink field zgyro.
Angular speed around Z axis
lat: f32MAVLink field lat.
Latitude (lower precision). Both this and the lat_int field should be set.
lon: f32MAVLink field lon.
Longitude (lower precision). Both this and the lon_int field should be set.
alt: f32MAVLink field alt.
Altitude
std_dev_horz: f32MAVLink field std_dev_horz.
Horizontal position standard deviation
std_dev_vert: f32MAVLink field std_dev_vert.
Vertical position standard deviation
vn: f32MAVLink field vn.
True velocity in north direction in earth-fixed NED frame
ve: f32MAVLink field ve.
True velocity in east direction in earth-fixed NED frame
vd: f32MAVLink field vd.
True velocity in down direction in earth-fixed NED frame
lat_int: i32MAVLink field lat_int.
Latitude (higher precision). If 0, recipients should use the lat field value (otherwise this field is preferred).
lon_int: i32MAVLink field lon_int.
Longitude (higher precision). If 0, recipients should use the lon field value (otherwise this field is preferred).
Implementations§
Source§impl SimState
impl SimState
Sourcepub const fn spec() -> MessageInfo
pub const fn spec() -> MessageInfo
Returns specification for this message.
Sourcepub const fn message_id() -> MessageId
pub const fn message_id() -> MessageId
Message ID.
Sourcepub const fn min_supported_mavlink_version() -> MavLinkVersion
pub const fn min_supported_mavlink_version() -> MavLinkVersion
Minimum supported MAVLink version for this message.
Trait Implementations§
Source§impl<'de> Deserialize<'de> for SimState
impl<'de> Deserialize<'de> for SimState
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 IntoPayload for SimState
impl IntoPayload for SimState
Source§impl MessageSpec for SimState
impl MessageSpec for SimState
Source§impl MessageSpecStatic for SimState
impl MessageSpecStatic for SimState
Source§fn spec() -> MessageInfo
fn spec() -> MessageInfo
Source§fn message_id() -> MessageId
fn message_id() -> MessageId
ID.Source§fn min_supported_mavlink_version() -> MavLinkVersion
fn min_supported_mavlink_version() -> MavLinkVersion
Source§impl NamedType for SimState
impl NamedType for SimState
fn sid() -> SpectaID
Source§fn named_data_type(
type_map: &mut TypeCollection,
generics: &[DataType],
) -> NamedDataType
fn named_data_type( type_map: &mut TypeCollection, generics: &[DataType], ) -> NamedDataType
Source§fn definition_named_data_type(type_map: &mut TypeCollection) -> NamedDataType
fn definition_named_data_type(type_map: &mut TypeCollection) -> NamedDataType
Source§impl Type for SimState
impl Type for SimState
Source§fn inline(type_map: &mut TypeCollection, generics: Generics<'_>) -> DataType
fn inline(type_map: &mut TypeCollection, generics: Generics<'_>) -> DataType
Source§fn reference(type_map: &mut TypeCollection, generics: &[DataType]) -> Reference
fn reference(type_map: &mut TypeCollection, generics: &[DataType]) -> Reference
definition will be put into the type map.