pub struct MAVLinkV1MessageRaw(/* private fields */);
Expand description
Byte buffer containing the raw representation of a MAVLink 1 message beginning with the STX marker.
Follow protocol definition: https://mavlink.io/en/guide/serialization.html#v1_packet_format. Maximum size is 263 bytes.
Implementations§
Source§impl MAVLinkV1MessageRaw
impl MAVLinkV1MessageRaw
Sourcepub const fn new() -> MAVLinkV1MessageRaw
pub const fn new() -> MAVLinkV1MessageRaw
Create an new raw MAVLink 1 message filled with zeros.
Sourcepub fn payload_length(&self) -> u8
pub fn payload_length(&self) -> u8
Size of the payload of the message
Sourcepub fn component_id(&self) -> u8
pub fn component_id(&self) -> u8
Message sender Component ID
Sourcepub fn message_id(&self) -> u8
pub fn message_id(&self) -> u8
Message ID
Sourcepub fn checksum(&self) -> u16
pub fn checksum(&self) -> u16
CRC-16 checksum field of the message
Sourcepub fn has_valid_crc<M>(&self) -> boolwhere
M: Message,
pub fn has_valid_crc<M>(&self) -> boolwhere
M: Message,
Checks wether the message’s CRC-16 checksum calculation matches its checksum field.
Sourcepub fn serialize_message<M>(&mut self, header: MavHeader, message: &M)where
M: Message,
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.
pub fn serialize_message_data<D>(&mut self, header: MavHeader, message_data: &D)where
D: MessageData,
Trait Implementations§
Source§impl Clone for MAVLinkV1MessageRaw
impl Clone for MAVLinkV1MessageRaw
Source§fn clone(&self) -> MAVLinkV1MessageRaw
fn clone(&self) -> MAVLinkV1MessageRaw
Returns a duplicate of the value. Read more
1.0.0 · Source§const fn clone_from(&mut self, source: &Self)
const fn clone_from(&mut self, source: &Self)
Performs copy-assignment from
source
. Read moreSource§impl Debug for MAVLinkV1MessageRaw
impl Debug for MAVLinkV1MessageRaw
Source§impl Default for MAVLinkV1MessageRaw
impl Default for MAVLinkV1MessageRaw
Source§fn default() -> MAVLinkV1MessageRaw
fn default() -> MAVLinkV1MessageRaw
Returns the “default value” for a type. Read more
Source§impl PartialEq for MAVLinkV1MessageRaw
impl PartialEq for MAVLinkV1MessageRaw
impl Copy for MAVLinkV1MessageRaw
impl Eq for MAVLinkV1MessageRaw
impl StructuralPartialEq for MAVLinkV1MessageRaw
Auto Trait Implementations§
impl Freeze for MAVLinkV1MessageRaw
impl RefUnwindSafe for MAVLinkV1MessageRaw
impl Send for MAVLinkV1MessageRaw
impl Sync for MAVLinkV1MessageRaw
impl Unpin for MAVLinkV1MessageRaw
impl UnwindSafe for MAVLinkV1MessageRaw
Blanket Implementations§
Source§impl<T> BorrowMut<T> for Twhere
T: ?Sized,
impl<T> BorrowMut<T> for Twhere
T: ?Sized,
Source§fn borrow_mut(&mut self) -> &mut T
fn borrow_mut(&mut self) -> &mut T
Mutably borrows from an owned value. Read more