Struct MAVLinkV2MessageRaw

Source
pub struct MAVLinkV2MessageRaw(/* private fields */);
Expand description

Byte buffer containing the raw representation of a MAVLink 2 message beginning with the STX marker.

Follow protocol definition: https://mavlink.io/en/guide/serialization.html#mavlink2_packet_format. Maximum size is 280 bytes.

Implementations§

Source§

impl MAVLinkV2MessageRaw

Source

pub const fn new() -> MAVLinkV2MessageRaw

Create an new raw MAVLink 2 message filled with zeros.

Source

pub fn header(&self) -> &[u8]

Reference to the 9 byte header slice of the message

Source

pub fn payload_length(&self) -> u8

Size of the payload of the message

Source

pub fn incompatibility_flags(&self) -> u8

Incompatiblity flags of the message

Currently the only supported incompatebility flag is MAVLINK_IFLAG_SIGNED.

Source

pub fn incompatibility_flags_mut(&mut self) -> &mut u8

Mutable reference to the incompatiblity flags of the message

Currently the only supported incompatebility flag is MAVLINK_IFLAG_SIGNED.

Source

pub fn compatibility_flags(&self) -> u8

Compatibility Flags of the message

Source

pub fn sequence(&self) -> u8

Packet sequence number

Source

pub fn system_id(&self) -> u8

Message sender System ID

Source

pub fn component_id(&self) -> u8

Message sender Component ID

Source

pub fn message_id(&self) -> u32

Message ID

Source

pub fn payload(&self) -> &[u8]

Reference to the payload byte slice of the message

Source

pub fn checksum(&self) -> u16

CRC-16 checksum field of the message

Source

pub fn checksum_bytes(&self) -> &[u8]

Reference to the 2 checksum bytes of the message

Signature Link ID

If the message is not signed this 0.

Mutable reference to the signature Link ID

Source

pub fn signature_timestamp(&self) -> u64

Message signature timestamp

The timestamp is a 48 bit number with units of 10 microseconds since 1st January 2015 GMT. The offset since 1st January 1970 (the unix epoch) is 1420070400 seconds. Since all timestamps generated must be at least 1 more than the previous timestamp this timestamp may get ahead of GMT time if there is a burst of packets at a rate of more than 100000 packets per second.

Source

pub fn signature_timestamp_bytes(&self) -> &[u8]

48 bit signature timestamp byte slice

If the message is not signed this contains zeros.

Source

pub fn signature_timestamp_bytes_mut(&mut self) -> &mut [u8]

Mutable reference to the 48 bit signature timestams byte slice

Source

pub fn signature_value(&self) -> &[u8]

Reference to the 48 bit message signature byte slice

If the message is not signed this contains zeros.

Source

pub fn signature_value_mut(&mut self) -> &mut [u8]

Mutable reference to the 48 bit message signature byte slice

Source

pub fn has_valid_crc<M>(&self) -> bool
where M: Message,

Checks wether the message’s CRC-16 checksum calculation matches its checksum field.

Source

pub fn calculate_signature( &self, secret_key: &[u8], target_buffer: &mut [u8; 6], )

Calculates the messages sha256_48 signature.

This calculates the SHA-256 checksum of messages appended to the 32 byte secret key and copies the first 6 bytes of the result into the target buffer.

Source

pub fn raw_bytes(&self) -> &[u8]

Raw byte slice of the message

Source

pub fn serialize_message<M>(&mut self, header: MavHeader, message: &M)
where M: Message,

Serialize a Message with a given header into this raw message buffer.

This does not set any compatiblity or incompatiblity flags.

Source

pub fn serialize_message_for_signing<M>( &mut self, header: MavHeader, message: &M, )
where M: Message,

Serialize a Message with a given header into this raw message buffer and sets the MAVLINK_IFLAG_SIGNED incompatiblity flag.

This does not update the message’s signature fields. This does not set any compatiblity flags.

Source

pub fn serialize_message_data<D>(&mut self, header: MavHeader, message_data: &D)
where D: MessageData,

Trait Implementations§

Source§

impl Clone for MAVLinkV2MessageRaw

Source§

fn clone(&self) -> MAVLinkV2MessageRaw

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 MAVLinkV2MessageRaw

Source§

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

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

impl Default for MAVLinkV2MessageRaw

Source§

fn default() -> MAVLinkV2MessageRaw

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

impl PartialEq for MAVLinkV2MessageRaw

Source§

fn eq(&self, other: &MAVLinkV2MessageRaw) -> 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 Copy for MAVLinkV2MessageRaw

Source§

impl Eq for MAVLinkV2MessageRaw

Source§

impl StructuralPartialEq for MAVLinkV2MessageRaw

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

Source§

type Output = T

Should always be Self
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.