Struct mavio::Frame

source ·
pub struct Frame<V: MaybeVersioned> { /* private fields */ }
Expand description

MAVLink frame.

Represents MAVLink1 or MAVLink2 packet.

§Protocol Version

All MAVLink frames are always belong to a specific MAVLink protocol version. However, for the sake of generality, this library provides a way to deal with MAVLink protocol version both explicitly by operating on Frame<V1> / Frame<V2> and implicitly through Frame<Versionless>. The latter can be obtained by Frame::into_versionless and converted into protocol-specific form through Frame::try_into_versioned. Both versionless and versioned forms of a frame could be correctly decoded into the corresponding MAVLink message.

§Encoding / Decoding

Frames can be decoded into the corresponding MAVLink message by Frame::decode method. This requires appropriate MAVLink dialect to be generated by mavspec. All autogenerated dialects can be found in the mavio::dialects module.

To encode MAVLink message into a frame, you should use FrameBuilder::message as described in construction section.

§Construction

Since MAVLink frames has a complex internal structure that depends on MavLinkVersion, encoded Message and presence of Signature, there are is direct no constructor for this struct. Frame can be either received as they were sent by remote or built from FrameBuilder.

Use Frame::builder to create new frames via builder and Frame::add_signature (for Frame<V2> only) to sign frames.

Implementations§

source§

impl Frame<Versionless>

source

pub fn builder( ) -> FrameBuilder<Versionless, Unset, Unset, Unset, Unset, Unset, Unset, Unset, Unset>

Instantiates an empty builder for Frame.

source§

impl<V: MaybeVersioned> Frame<V>

source

pub fn header(&self) -> &Header<V>

Frame Header.

source

pub fn version(&self) -> MavLinkVersion

MAVLink protocol version defined by Header.

source

pub fn payload_length(&self) -> PayloadLength

Payload length.

Indicates length of the following payload section. This may be affected by payload truncation.

source

pub fn sequence(&self) -> Sequence

Packet sequence number.

Used to detect packet loss. Components increment value for each message sent.

source

pub fn system_id(&self) -> SystemId

System ID.

ID of system (vehicle) sending the message. Used to differentiate systems on network.

Note that the broadcast address 0 may not be used in this field as it is an invalid source address.

source

pub fn component_id(&self) -> ComponentId

Component ID.

ID of component sending the message. Used to differentiate components in a system (e.g. autopilot and a camera). Use appropriate values in MAV_COMPONENT.

Note that the broadcast address MAV_COMP_ID_ALL may not be used in this field as it is an invalid source address.

source

pub fn message_id(&self) -> MessageId

Message ID.

ID of MAVLink message. Defines how payload will be encoded and decoded.

source

pub fn payload(&self) -> &Payload

Payload data.

Message data. Content depends on message type (i.e. message_id).

Returns an instance of Payload. If you are interested in payload bytes, use Payload::bytes.

source

pub fn checksum(&self) -> Checksum

MAVLink packet checksum.

CRC-16/MCRF4XX checksum for message (excluding magic byte).

Includes CRC_EXTRA byte.

Checksum is encoded with little endian (low byte, high byte).

source

pub fn is_signed(&self) -> bool

Returns true if frame is signed.

Returns true if Frame contains Signature. Correctness of signature is not validated.

For MAVLink 1 frames always returns false.

source

pub fn signature(&self) -> Option<&Signature>

MAVLink 2 signature.

Returns signature that ensures the link is tamper-proof.

Available only for signed MAVLink 2 frames. For MAVLink 1 always return None.

§MavFrame::signature.
source

pub fn remove_signature(&mut self)

Removes MAVLink 2 signature from frame.

Applicable only for MAVLink 2 frames. MAVLink 1 frames will be kept untouched.

MavFrame::remove_signature

source

pub fn body_length(&self) -> usize

Body length.

Returns the length of the entire Frame body. The frame body consist of Payload::bytes, Checksum, and optional Signature (for MAVLink 2 protocol).

source

pub fn calculate_crc(&self, crc_extra: CrcExtra) -> Checksum

Calculates CRC for frame within crc_extra.

Provided crc_extra depends on a dialect and contains a digest of message XML definition.

source

pub fn validate_checksum<D: Dialect>(&self) -> Result<()>

Validates frame in the context of specific dialect.

Receives dialect specification in dialect_spec, ensures that message with such ID exists in this dialect, and compares checksums using EXTRA_CRC.

§Errors
source

pub fn validate_checksum_with_crc_extra( &self, crc_extra: CrcExtra ) -> Result<(), ChecksumError>

Validates frame’s checksum using provided crc_extra.

§Errors

Returns ChecksumError if checksum validation failed.

source

pub fn matches_version<Version: Versioned>(&self, version: Version) -> bool

Checks that frame has MAVLink version equal to the provided one.

§MavFrame::matches_version
source

pub fn try_into_versioned<Version: MaybeVersioned>( self ) -> Result<Frame<Version>, VersionError>

Attempts to transform frame into its versioned form.

This method never changes the internal MAVLink protocol version. It will return an error, if conversion is not possible.

source

pub fn try_to_versioned<Version: MaybeVersioned>( &self ) -> Result<Frame<Version>, VersionError>

Attempts to create frame of specified version from the existing one.

This method never changes the internal MAVLink protocol version. It will return an error, if conversion is not possible.

source

pub fn into_versionless(self) -> Frame<Versionless>

Forget about frame’s version transforming it into a Versionless variant.

source

pub fn to_versionless(&self) -> Frame<Versionless>

Forget about frame’s version transforming it into a Versionless variant.

source

pub fn into_mav_frame(self) -> MavFrame

Converts this frame into a dynamic MavFrame.

source

pub fn decode<D: Dialect>(&self) -> Result<D>

Decodes frame into a message of particular MAVLink dialect.

Performs Frame::checksum validation before returning decoded message.

§Usage
use mavio::dialects::minimal;
use mavio::dialects::minimal::Minimal;
use mavio::Frame;

let frame = // ... obtain a frame

// Decode the frame within `minimal` dialect and match result over available dialect messages
match frame.decode().unwrap() {
    Minimal::ProtocolVersion(_) => {}
    Minimal::Heartbeat(_) => {}
}
§Errors
source

pub fn upgrade_with_crc_extra(&mut self, crc_extra: CrcExtra)

Upgrades a frame in-place to MAVLink 2 protocol version using provided CRC_EXTRA.

The opposite is not possible since we need to know exact payload length.

source§

impl<V: Versioned> Frame<V>

source

pub fn to_builder( &self ) -> FrameBuilder<V, HasPayloadLen, Sequenced, HasSysId, HasCompId, HasMsgId, HasPayload, Unset, Unset>

Create FrameBuilder populated with current frame data.

It is not possible to simply change a particular frame field since MAVLink frame data is tightly packed together, covered by CRC, and, in the case of MAVLink 2 protocol, is potentially signed. Moreover, to alter a frame correctly we need a CrcExtra byte which is a part of a dialect, not the frame itself.

This method provides a limited capability to alter frame data by creating a FrameBuilder populated with data of the current frame. For MAVLink 2 frames this will drop frame’s signature and IncompatFlags::MAVLINK_IFLAG_SIGNED in incompat_flags rendering frame unsigned. This process also requires from caller to provide a CrcExtra value to encoded message since checksum will be dropped as well and the information required to its this recalculation is not stored within MAVLink frame itself.

It is not possible to rebuild Versionless frames since MAVLink 2 Payload may contain extension fields and its trailing zero bytes are truncated which means it is not possible to reconstruct MAVLink 1 payload_length when downgrading frame protocol version.

source§

impl Frame<V2>

source

pub fn incompat_flags(&self) -> IncompatFlags

Incompatibility flags for MAVLink 2 header.

Flags that must be understood for MAVLink compatibility (implementation discards packet if it does not understand flag).

See: MAVLink 2 incompatibility flags.

source

pub fn compat_flags(&self) -> CompatFlags

Compatibility flags for MAVLink 2 header.

Flags that can be ignored if not understood (implementation can still handle packet even if it does not understand flag).

See: MAVLink 2 compatibility flags.

MAVLink 2 signature link_id, an 8-bit identifier of a MAVLink channel.

Peers may have different semantics or rules for different links. For example, some links may have higher priority over another during routing. Or even different secret keys for authorization.

Available only for signed MAVLink 2 frame. For MAVLink 1 always return None.

source

pub fn timestamp(&self) -> Option<MavTimestamp>

MAVLink 2 signature MavTimestamp, a 48-bit value that specifies the moment when message was sent.

The unit of measurement is the number of millisecond * 10 since MAVLink epoch (1st January 2015 GMT).

According to MAVLink protocol, the sender must guarantee that the next timestamp is greater than the previous one.

Available only for signed MAVLink 2 frame. For MAVLink 1 always return None.

source

pub fn add_signature( &mut self, signer: &mut dyn Sign, conf: &SigningConf ) -> &mut Self

Adds signature to MAVLink 2 frame.

Signs MAVLink 2 frame with provided instance of signer that implements Sign trait and signature configuration specified as SigningConf.

source

pub fn validate_signature( &self, signer: &mut dyn Sign, key: &SecretKey ) -> Result<(), SignatureError>

Validates frame signature using a signer and a secret key.

Returns SignatureError if frame missing a signature or have an incorrect one.

Trait Implementations§

source§

impl<V: Clone + MaybeVersioned> Clone for Frame<V>

source§

fn clone(&self) -> Frame<V>

Returns a copy 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<V: Debug + MaybeVersioned> Debug for Frame<V>

source§

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

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

impl<'de, V> Deserialize<'de> for Frame<V>
where V: Deserialize<'de> + MaybeVersioned,

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<V: MaybeVersioned> From<Frame<V>> for MavFrame

source§

fn from(value: Frame<V>) -> Self

Converts to this type from the input type.
source§

impl<V> Serialize for Frame<V>

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<V: MaybeVersioned> TryFrom<MavFrame> for Frame<V>

§

type Error = VersionError

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

fn try_from(value: MavFrame) -> Result<Self, VersionError>

Performs the conversion.
source§

impl<V: MaybeVersioned> TryUpdateFrom<&MavFrame> for Frame<V>

§

type Error = VersionError

Error, that may be thrown during update.
source§

fn check_try_update_from(&self, value: &&MavFrame) -> Result<(), Self::Error>

Checks, that update is possible. Read more
source§

unsafe fn update_from_unchecked(&mut self, value: &MavFrame)

Performs the update without checking, whether update is possible. Read more
source§

fn try_update_from(&mut self, value: T) -> Result<(), Self::Error>

Performs the update. Read more
source§

impl<V: MaybeVersioned> TryUpdateFrom<&dyn Message> for Frame<V>

source§

fn try_update_from(&mut self, value: &dyn Message) -> Result<(), Self::Error>

Updates a frame with the data from the provided message.

Replaces the following fields, that are guaranteed to be correct:

This method will strip Frame::signature. Make sure, that you know, how to sign the updated frame afterward.

§

type Error = SpecError

Error, that may be thrown during update.
source§

fn check_try_update_from(&self, value: &&dyn Message) -> Result<(), Self::Error>

Checks, that update is possible. Read more
source§

unsafe fn update_from_unchecked(&mut self, value: &dyn Message)

Performs the update without checking, whether update is possible. Read more

Auto Trait Implementations§

§

impl<V> Freeze for Frame<V>

§

impl<V> RefUnwindSafe for Frame<V>
where V: RefUnwindSafe,

§

impl<V> Send for Frame<V>

§

impl<V> Sync for Frame<V>

§

impl<V> Unpin for Frame<V>
where V: Unpin,

§

impl<V> UnwindSafe for Frame<V>
where V: UnwindSafe,

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> 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> Same for T

§

type Output = T

Should always be Self
source§

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

§

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>,

§

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>,

§

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>,