pub struct VisionPositionEstimate {
pub usec: u64,
pub x: f32,
pub y: f32,
pub z: f32,
pub roll: f32,
pub pitch: f32,
pub yaw: f32,
pub covariance: [f32; 21],
pub reset_counter: u8,
}Expand description
MAVLink VISION_POSITION_ESTIMATE message.
The minimum supported MAVLink version is MAVLink 1.
§Description
Local position/attitude estimate from a vision source.
§Encoding/Decoding
Message encoding/decoding are provided by implementing core::convert::TryFrom<Payload> for
VisionPositionEstimate (encoding) and [IntoPayload] (decoding) traits.
These traits are implemented by Message proc macro.
Fields§
§usec: u64MAVLink field usec.
Timestamp (UNIX time or time since system boot)
x: f32MAVLink field x.
Local X position
y: f32MAVLink field y.
Local Y position
z: f32MAVLink field z.
Local Z position
roll: f32MAVLink field roll.
Roll angle
pitch: f32MAVLink field pitch.
Pitch angle
yaw: f32MAVLink field yaw.
Yaw angle
covariance: [f32; 21]MAVLink field covariance.
Row-major representation of pose 6x6 cross-covariance matrix upper right triangle (states: x, y, z, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array.
reset_counter: u8MAVLink field reset_counter.
Estimate reset counter. This should be incremented when the estimate resets in any of the dimensions (position, velocity, attitude, angular speed). This is designed to be used when e.g an external SLAM system detects a loop-closure and the estimate jumps.
Implementations§
Source§impl VisionPositionEstimate
impl VisionPositionEstimate
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 Clone for VisionPositionEstimate
impl Clone for VisionPositionEstimate
Source§fn clone(&self) -> VisionPositionEstimate
fn clone(&self) -> VisionPositionEstimate
1.0.0 · Source§fn clone_from(&mut self, source: &Self)
fn clone_from(&mut self, source: &Self)
source. Read moreSource§impl Debug for VisionPositionEstimate
impl Debug for VisionPositionEstimate
Source§impl Default for VisionPositionEstimate
impl Default for VisionPositionEstimate
Source§impl<'de> Deserialize<'de> for VisionPositionEstimate
impl<'de> Deserialize<'de> for VisionPositionEstimate
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 From<VisionPositionEstimate> for Common
impl From<VisionPositionEstimate> for Common
Source§fn from(value: VisionPositionEstimate) -> Self
fn from(value: VisionPositionEstimate) -> Self
Source§impl IntoPayload for VisionPositionEstimate
impl IntoPayload for VisionPositionEstimate
Source§impl MessageSpec for VisionPositionEstimate
impl MessageSpec for VisionPositionEstimate
Source§impl MessageSpecStatic for VisionPositionEstimate
impl MessageSpecStatic for VisionPositionEstimate
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 VisionPositionEstimate
impl NamedType for VisionPositionEstimate
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 PartialEq for VisionPositionEstimate
impl PartialEq for VisionPositionEstimate
Source§impl Serialize for VisionPositionEstimate
impl Serialize for VisionPositionEstimate
Source§impl TryFrom<&Payload> for VisionPositionEstimate
impl TryFrom<&Payload> for VisionPositionEstimate
Source§impl Type for VisionPositionEstimate
impl Type for VisionPositionEstimate
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.