VisionPositionEstimate

Struct VisionPositionEstimate 

Source
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: u64

MAVLink field usec.

Timestamp (UNIX time or time since system boot)

§x: f32

MAVLink field x.

Local X position

§y: f32

MAVLink field y.

Local Y position

§z: f32

MAVLink field z.

Local Z position

§roll: f32

MAVLink field roll.

Roll angle

§pitch: f32

MAVLink field pitch.

Pitch angle

§yaw: f32

MAVLink 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: u8

MAVLink 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

Source

pub const ID: MessageId = 102u32

MavLink message ID.

Source

pub const fn spec() -> MessageInfo

Returns specification for this message.

Source

pub const fn message_id() -> MessageId

Message ID.

Source

pub const fn crc_extra() -> CrcExtra

Message CRC_EXTRA.

Minimum supported MAVLink version for this message.

Trait Implementations§

Source§

impl Clone for VisionPositionEstimate

Source§

fn clone(&self) -> VisionPositionEstimate

Returns a duplicate of the value. Read more
1.0.0 · Source§

fn clone_from(&mut self, source: &Self)

Performs copy-assignment from source. Read more
Source§

impl Debug for VisionPositionEstimate

Source§

fn fmt(&self, f: &mut Formatter<'_>) -> Result

Formats the value using the given formatter. Read more
Source§

impl Default for VisionPositionEstimate

Source§

fn default() -> Self

Returns the “default value” for a type. Read more
Source§

impl<'de> Deserialize<'de> for VisionPositionEstimate

Source§

fn deserialize<__D>(__deserializer: __D) -> Result<Self, __D::Error>
where __D: Deserializer<'de>,

Deserialize this value from the given Serde deserializer. Read more
Source§

impl From<VisionPositionEstimate> for Common

Source§

fn from(value: VisionPositionEstimate) -> Self

Converts to this type from the input type.
Source§

impl IntoPayload for VisionPositionEstimate

Source§

fn encode(&self, version: MavLinkVersion) -> Result<Payload, SpecError>

Encodes message into MAVLink payload. Read more
Source§

impl MessageSpec for VisionPositionEstimate

Source§

fn id(&self) -> MessageId

MAVLink message ID. Read more
Minimum supported MAVLink protocol version. Read more
Source§

fn crc_extra(&self) -> CrcExtra

Message EXTRA_CRC calculated from message XML definition. Read more
Source§

impl MessageSpecStatic for VisionPositionEstimate

Source§

fn spec() -> MessageInfo

Returns specification for this message.
Source§

fn message_id() -> MessageId

Message ID.
Source§

fn crc_extra() -> CrcExtra

Message CRC_EXTRA.
Minimum supported MAVLink version for this message.
Source§

impl NamedType for VisionPositionEstimate

Source§

fn sid() -> SpectaID

Source§

fn named_data_type( type_map: &mut TypeCollection, generics: &[DataType], ) -> NamedDataType

this is equivalent to Type::inline but returns a NamedDataType instead.
Source§

fn definition_named_data_type(type_map: &mut TypeCollection) -> NamedDataType

this is equivalent to [Type::definition] but returns a NamedDataType instead.
Source§

impl PartialEq for VisionPositionEstimate

Source§

fn eq(&self, other: &VisionPositionEstimate) -> bool

Tests for self and other values to be equal, and is used by ==.
1.0.0 · Source§

fn ne(&self, other: &Rhs) -> bool

Tests for !=. The default implementation is almost always sufficient, and should not be overridden without very good reason.
Source§

impl Serialize for VisionPositionEstimate

Source§

fn serialize<__S>(&self, __serializer: __S) -> Result<__S::Ok, __S::Error>
where __S: Serializer,

Serialize this value into the given Serde serializer. Read more
Source§

impl TryFrom<&Payload> for VisionPositionEstimate

Source§

type Error = SpecError

The type returned in the event of a conversion error.
Source§

fn try_from(value: &Payload) -> Result<Self, Self::Error>

Performs the conversion.
Source§

impl Type for VisionPositionEstimate

Source§

fn inline(type_map: &mut TypeCollection, generics: Generics<'_>) -> DataType

Returns the definition of a type using the provided generics. Read more
Source§

fn reference(type_map: &mut TypeCollection, generics: &[DataType]) -> Reference

Generates a datatype corresponding to a reference to this type, as determined by its category. Getting a reference to a type implies that it should belong in the type map (since it has to be referenced from somewhere), so the output of definition will be put into the type map.
Source§

impl Flatten for VisionPositionEstimate

Source§

impl Message for VisionPositionEstimate

Source§

impl StructuralPartialEq for VisionPositionEstimate

Auto Trait Implementations§

Blanket Implementations§

Source§

impl<T> Any for T
where T: 'static + ?Sized,

Source§

fn type_id(&self) -> TypeId

Gets the TypeId of self. Read more
Source§

impl<T> Borrow<T> for T
where T: ?Sized,

Source§

fn borrow(&self) -> &T

Immutably borrows from an owned value. Read more
Source§

impl<T> BorrowMut<T> for T
where T: ?Sized,

Source§

fn borrow_mut(&mut self) -> &mut T

Mutably borrows from an owned value. Read more
Source§

impl<T> CloneToUninit for T
where T: Clone,

Source§

unsafe fn clone_to_uninit(&self, dest: *mut u8)

🔬This is a nightly-only experimental API. (clone_to_uninit)
Performs copy-assignment from self to dest. Read more
Source§

impl<T> From<T> for T

Source§

fn from(t: T) -> T

Returns the argument unchanged.

Source§

impl<T, U> Into<U> for T
where U: From<T>,

Source§

fn into(self) -> U

Calls U::from(self).

That is, this conversion is whatever the implementation of From<T> for U chooses to do.

Source§

impl<T> ToOwned for T
where T: Clone,

Source§

type Owned = T

The resulting type after obtaining ownership.
Source§

fn to_owned(&self) -> T

Creates owned data from borrowed data, usually by cloning. Read more
Source§

fn clone_into(&self, target: &mut T)

Uses borrowed data to replace owned data, usually by cloning. Read more
Source§

impl<T, U> TryFrom<U> for T
where U: Into<T>,

Source§

type Error = Infallible

The type returned in the event of a conversion error.
Source§

fn try_from(value: U) -> Result<T, <T as TryFrom<U>>::Error>

Performs the conversion.
Source§

impl<T, U> TryInto<U> for T
where U: TryFrom<T>,

Source§

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

The type returned in the event of a conversion error.
Source§

fn try_into(self) -> Result<U, <U as TryFrom<T>>::Error>

Performs the conversion.
Source§

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