1#![cfg_attr(not(feature = "std"), no_std)]
22#![cfg_attr(all(any(docsrs, doc), not(doctest)), feature(doc_auto_cfg))]
23#![deny(clippy::all)]
24#![warn(clippy::use_self)]
25
26use core::result::Result;
27
28#[cfg(feature = "std")]
29use std::io::{Read, Write};
30
31pub mod utils;
32#[allow(unused_imports)]
33use utils::{remove_trailing_zeroes, RustDefault};
34
35#[cfg(feature = "serde")]
36use serde::{Deserialize, Serialize};
37
38pub mod peek_reader;
39use peek_reader::PeekReader;
40
41use crate::{bytes::Bytes, error::ParserError};
42
43use crc_any::CRCu16;
44
45pub mod bytes;
46pub mod bytes_mut;
47#[cfg(feature = "std")]
48mod connection;
49pub mod error;
50#[cfg(feature = "std")]
51pub use self::connection::{connect, Connectable, MavConnection};
52
53#[cfg(feature = "tokio-1")]
54mod async_connection;
55#[cfg(feature = "tokio-1")]
56pub use self::async_connection::{connect_async, AsyncConnectable, AsyncMavConnection};
57
58#[cfg(feature = "tokio-1")]
59pub mod async_peek_reader;
60#[cfg(feature = "tokio-1")]
61use async_peek_reader::AsyncPeekReader;
62
63#[cfg(any(feature = "embedded", feature = "embedded-hal-02"))]
64pub mod embedded;
65#[cfg(any(feature = "embedded", feature = "embedded-hal-02"))]
66use embedded::{Read, Write};
67
68#[cfg(not(feature = "signing"))]
69type SigningData = ();
70#[cfg(feature = "signing")]
71mod signing;
72#[cfg(feature = "signing")]
73pub use self::signing::{SigningConfig, SigningData};
74#[cfg(feature = "signing")]
75use sha2::{Digest, Sha256};
76
77#[cfg(feature = "arbitrary")]
78use arbitrary::Arbitrary;
79
80#[cfg(any(feature = "std", feature = "tokio-1"))]
81mod connectable;
82#[cfg(any(feature = "std", feature = "tokio-1"))]
83pub use connectable::{
84 ConnectionAddress, FileConnectable, SerialConnectable, TcpConnectable, UdpConnectable,
85};
86
87pub const MAX_FRAME_SIZE: usize = 280;
88
89pub trait Message
90where
91 Self: Sized,
92{
93 fn message_id(&self) -> u32;
94 fn message_name(&self) -> &'static str;
95
96 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize;
98
99 fn parse(
100 version: MavlinkVersion,
101 msgid: u32,
102 payload: &[u8],
103 ) -> Result<Self, error::ParserError>;
104
105 fn message_id_from_name(name: &str) -> Result<u32, &'static str>;
106 fn default_message_from_id(id: u32) -> Result<Self, &'static str>;
107 #[cfg(feature = "arbitrary")]
108 fn random_message_from_id<R: rand::RngCore>(id: u32, rng: &mut R)
109 -> Result<Self, &'static str>;
110 fn extra_crc(id: u32) -> u8;
111}
112
113pub trait MessageData: Sized {
114 type Message: Message;
115
116 const ID: u32;
117 const NAME: &'static str;
118 const EXTRA_CRC: u8;
119 const ENCODED_LEN: usize;
120
121 fn ser(&self, version: MavlinkVersion, payload: &mut [u8]) -> usize;
122 fn deser(version: MavlinkVersion, payload: &[u8]) -> Result<Self, ParserError>;
123}
124
125#[derive(Debug, Copy, Clone, PartialEq, Eq)]
127#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
128#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
129pub struct MavHeader {
130 pub system_id: u8,
131 pub component_id: u8,
132 pub sequence: u8,
133}
134
135#[derive(Debug, Copy, Clone, PartialEq, Eq)]
137#[cfg_attr(feature = "serde", derive(Serialize))]
138#[cfg_attr(feature = "serde", serde(tag = "type"))]
139#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
140pub enum MavlinkVersion {
141 V1,
142 V2,
143}
144
145pub const MAV_STX: u8 = 0xFE;
147
148pub const MAV_STX_V2: u8 = 0xFD;
150
151impl Default for MavHeader {
154 fn default() -> Self {
155 Self {
156 system_id: 255,
157 component_id: 0,
158 sequence: 0,
159 }
160 }
161}
162
163#[derive(Debug, Clone)]
167#[cfg_attr(feature = "serde", derive(Serialize))]
168#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
169pub struct MavFrame<M: Message> {
170 pub header: MavHeader,
171 pub msg: M,
172 pub protocol_version: MavlinkVersion,
173}
174
175impl<M: Message> MavFrame<M> {
176 pub fn ser(&self, buf: &mut [u8]) -> usize {
180 let mut buf = bytes_mut::BytesMut::new(buf);
181
182 let mut payload_buf = [0u8; 255];
184 let payload_len = self.msg.ser(self.protocol_version, &mut payload_buf);
185
186 buf.put_u8(self.header.sequence);
205 buf.put_u8(self.header.system_id);
206 buf.put_u8(self.header.component_id);
207
208 match self.protocol_version {
210 MavlinkVersion::V2 => {
211 let bytes: [u8; 4] = self.msg.message_id().to_le_bytes();
212 buf.put_slice(&bytes[..3]);
213 }
214 MavlinkVersion::V1 => {
215 buf.put_u8(self.msg.message_id() as u8); }
217 }
218
219 buf.put_slice(&payload_buf[..payload_len]);
220 buf.len()
221 }
222
223 pub fn deser(version: MavlinkVersion, input: &[u8]) -> Result<Self, ParserError> {
227 let mut buf = Bytes::new(input);
228
229 let sequence = buf.get_u8();
239 let system_id = buf.get_u8();
240 let component_id = buf.get_u8();
241 let header = MavHeader {
242 system_id,
243 component_id,
244 sequence,
245 };
246
247 let msg_id = match version {
248 MavlinkVersion::V2 => buf.get_u24_le(),
249 MavlinkVersion::V1 => buf.get_u8().into(),
250 };
251
252 M::parse(version, msg_id, buf.remaining_bytes()).map(|msg| Self {
253 header,
254 msg,
255 protocol_version: version,
256 })
257 }
258
259 pub fn header(&self) -> MavHeader {
261 self.header
262 }
263}
264
265pub fn calculate_crc(data: &[u8], extra_crc: u8) -> u16 {
266 let mut crc_calculator = CRCu16::crc16mcrf4cc();
267 crc_calculator.digest(data);
268
269 crc_calculator.digest(&[extra_crc]);
270 crc_calculator.get_crc()
271}
272
273#[derive(Debug, Clone, Copy, PartialEq, Eq)]
274pub enum ReadVersion {
276 Single(MavlinkVersion),
278 Any,
280}
281
282impl ReadVersion {
283 #[cfg(feature = "std")]
284 fn from_conn_cfg<C: MavConnection<M>, M: Message>(conn: &C) -> Self {
285 if conn.allow_recv_any_version() {
286 Self::Any
287 } else {
288 conn.protocol_version().into()
289 }
290 }
291 #[cfg(feature = "tokio-1")]
292 fn from_async_conn_cfg<C: AsyncMavConnection<M>, M: Message + Sync + Send>(conn: &C) -> Self {
293 if conn.allow_recv_any_version() {
294 Self::Any
295 } else {
296 conn.protocol_version().into()
297 }
298 }
299}
300
301impl From<MavlinkVersion> for ReadVersion {
302 fn from(value: MavlinkVersion) -> Self {
303 Self::Single(value)
304 }
305}
306
307pub fn read_versioned_msg<M: Message, R: Read>(
308 r: &mut PeekReader<R>,
309 version: ReadVersion,
310) -> Result<(MavHeader, M), error::MessageReadError> {
311 match version {
312 ReadVersion::Single(MavlinkVersion::V2) => read_v2_msg(r),
313 ReadVersion::Single(MavlinkVersion::V1) => read_v1_msg(r),
314 ReadVersion::Any => read_any_msg(r),
315 }
316}
317
318#[cfg(feature = "tokio-1")]
319pub async fn read_versioned_msg_async<M: Message, R: tokio::io::AsyncReadExt + Unpin>(
320 r: &mut AsyncPeekReader<R>,
321 version: ReadVersion,
322) -> Result<(MavHeader, M), error::MessageReadError> {
323 match version {
324 ReadVersion::Single(MavlinkVersion::V2) => read_v2_msg_async(r).await,
325 ReadVersion::Single(MavlinkVersion::V1) => read_v1_msg_async(r).await,
326 ReadVersion::Any => read_any_msg_async(r).await,
327 }
328}
329
330#[cfg(feature = "signing")]
331pub fn read_versioned_msg_signed<M: Message, R: Read>(
332 r: &mut PeekReader<R>,
333 version: ReadVersion,
334 signing_data: Option<&SigningData>,
335) -> Result<(MavHeader, M), error::MessageReadError> {
336 match version {
337 ReadVersion::Single(MavlinkVersion::V2) => read_v2_msg_inner(r, signing_data),
338 ReadVersion::Single(MavlinkVersion::V1) => read_v1_msg(r),
339 ReadVersion::Any => read_any_msg_inner(r, signing_data),
340 }
341}
342
343#[cfg(all(feature = "tokio-1", feature = "signing"))]
344pub async fn read_versioned_msg_async_signed<M: Message, R: tokio::io::AsyncReadExt + Unpin>(
345 r: &mut AsyncPeekReader<R>,
346 version: ReadVersion,
347 signing_data: Option<&SigningData>,
348) -> Result<(MavHeader, M), error::MessageReadError> {
349 match version {
350 ReadVersion::Single(MavlinkVersion::V2) => read_v2_msg_async_inner(r, signing_data).await,
351 ReadVersion::Single(MavlinkVersion::V1) => read_v1_msg_async(r).await,
352 ReadVersion::Any => read_any_msg_async_inner(r, signing_data).await,
353 }
354}
355
356#[derive(Debug, Copy, Clone, PartialEq, Eq)]
357pub struct MAVLinkV1MessageRaw([u8; 1 + Self::HEADER_SIZE + 255 + 2]);
362
363impl Default for MAVLinkV1MessageRaw {
364 fn default() -> Self {
365 Self::new()
366 }
367}
368
369impl MAVLinkV1MessageRaw {
370 const HEADER_SIZE: usize = 5;
371
372 pub const fn new() -> Self {
373 Self([0; 1 + Self::HEADER_SIZE + 255 + 2])
374 }
375
376 #[inline]
377 pub fn header(&self) -> &[u8] {
378 &self.0[1..=Self::HEADER_SIZE]
379 }
380
381 #[inline]
382 fn mut_header(&mut self) -> &mut [u8] {
383 &mut self.0[1..=Self::HEADER_SIZE]
384 }
385
386 #[inline]
387 pub fn payload_length(&self) -> u8 {
388 self.0[1]
389 }
390
391 #[inline]
392 pub fn sequence(&self) -> u8 {
393 self.0[2]
394 }
395
396 #[inline]
397 pub fn system_id(&self) -> u8 {
398 self.0[3]
399 }
400
401 #[inline]
402 pub fn component_id(&self) -> u8 {
403 self.0[4]
404 }
405
406 #[inline]
407 pub fn message_id(&self) -> u8 {
408 self.0[5]
409 }
410
411 #[inline]
412 pub fn payload(&self) -> &[u8] {
413 let payload_length: usize = self.payload_length().into();
414 &self.0[(1 + Self::HEADER_SIZE)..(1 + Self::HEADER_SIZE + payload_length)]
415 }
416
417 #[inline]
418 pub fn checksum(&self) -> u16 {
419 let payload_length: usize = self.payload_length().into();
420 u16::from_le_bytes([
421 self.0[1 + Self::HEADER_SIZE + payload_length],
422 self.0[1 + Self::HEADER_SIZE + payload_length + 1],
423 ])
424 }
425
426 #[inline]
427 fn mut_payload_and_checksum(&mut self) -> &mut [u8] {
428 let payload_length: usize = self.payload_length().into();
429 &mut self.0[(1 + Self::HEADER_SIZE)..(1 + Self::HEADER_SIZE + payload_length + 2)]
430 }
431
432 #[inline]
433 pub fn has_valid_crc<M: Message>(&self) -> bool {
434 let payload_length: usize = self.payload_length().into();
435 self.checksum()
436 == calculate_crc(
437 &self.0[1..(1 + Self::HEADER_SIZE + payload_length)],
438 M::extra_crc(self.message_id().into()),
439 )
440 }
441
442 pub fn raw_bytes(&self) -> &[u8] {
443 let payload_length = self.payload_length() as usize;
444 &self.0[..(1 + Self::HEADER_SIZE + payload_length + 2)]
445 }
446
447 fn serialize_stx_and_header_and_crc(
448 &mut self,
449 header: MavHeader,
450 msgid: u32,
451 payload_length: usize,
452 extra_crc: u8,
453 ) {
454 self.0[0] = MAV_STX;
455
456 let header_buf = self.mut_header();
457 header_buf.copy_from_slice(&[
458 payload_length as u8,
459 header.sequence,
460 header.system_id,
461 header.component_id,
462 msgid as u8,
463 ]);
464
465 let crc = calculate_crc(
466 &self.0[1..(1 + Self::HEADER_SIZE + payload_length)],
467 extra_crc,
468 );
469 self.0[(1 + Self::HEADER_SIZE + payload_length)
470 ..(1 + Self::HEADER_SIZE + payload_length + 2)]
471 .copy_from_slice(&crc.to_le_bytes());
472 }
473
474 pub fn serialize_message<M: Message>(&mut self, header: MavHeader, message: &M) {
475 let payload_buf = &mut self.0[(1 + Self::HEADER_SIZE)..(1 + Self::HEADER_SIZE + 255)];
476 let payload_length = message.ser(MavlinkVersion::V1, payload_buf);
477
478 let message_id = message.message_id();
479 self.serialize_stx_and_header_and_crc(
480 header,
481 message_id,
482 payload_length,
483 M::extra_crc(message_id),
484 );
485 }
486
487 pub fn serialize_message_data<D: MessageData>(&mut self, header: MavHeader, message_data: &D) {
488 let payload_buf = &mut self.0[(1 + Self::HEADER_SIZE)..(1 + Self::HEADER_SIZE + 255)];
489 let payload_length = message_data.ser(MavlinkVersion::V1, payload_buf);
490
491 self.serialize_stx_and_header_and_crc(header, D::ID, payload_length, D::EXTRA_CRC);
492 }
493}
494
495fn try_decode_v1<M: Message, R: Read>(
496 reader: &mut PeekReader<R>,
497) -> Result<Option<MAVLinkV1MessageRaw>, error::MessageReadError> {
498 let mut message = MAVLinkV1MessageRaw::new();
499 let whole_header_size = MAVLinkV1MessageRaw::HEADER_SIZE + 1;
500
501 message.0[0] = MAV_STX;
502 let header = &reader.peek_exact(whole_header_size)?[1..whole_header_size];
503 message.mut_header().copy_from_slice(header);
504 let packet_length = message.raw_bytes().len();
505 let payload_and_checksum = &reader.peek_exact(packet_length)?[whole_header_size..packet_length];
506 message
507 .mut_payload_and_checksum()
508 .copy_from_slice(payload_and_checksum);
509
510 if message.has_valid_crc::<M>() {
513 reader.consume(message.raw_bytes().len());
514 Ok(Some(message))
515 } else {
516 Ok(None)
517 }
518}
519
520#[cfg(feature = "tokio-1")]
521async fn try_decode_v1_async<M: Message, R: tokio::io::AsyncReadExt + Unpin>(
523 reader: &mut AsyncPeekReader<R>,
524) -> Result<Option<MAVLinkV1MessageRaw>, error::MessageReadError> {
525 let mut message = MAVLinkV1MessageRaw::new();
526
527 message.0[0] = MAV_STX;
528 let header = &reader.peek_exact(MAVLinkV1MessageRaw::HEADER_SIZE).await?
529 [..MAVLinkV1MessageRaw::HEADER_SIZE];
530 message.mut_header().copy_from_slice(header);
531 let packet_length = message.raw_bytes().len() - 1;
532 let payload_and_checksum =
533 &reader.peek_exact(packet_length).await?[MAVLinkV1MessageRaw::HEADER_SIZE..packet_length];
534 message
535 .mut_payload_and_checksum()
536 .copy_from_slice(payload_and_checksum);
537
538 if message.has_valid_crc::<M>() {
541 reader.consume(message.raw_bytes().len() - 1);
542 Ok(Some(message))
543 } else {
544 Ok(None)
545 }
546}
547
548pub fn read_v1_raw_message<M: Message, R: Read>(
551 reader: &mut PeekReader<R>,
552) -> Result<MAVLinkV1MessageRaw, error::MessageReadError> {
553 loop {
554 while reader.peek_exact(1)?[0] != MAV_STX {
556 reader.consume(1);
557 }
558
559 if let Some(msg) = try_decode_v1::<M, _>(reader)? {
560 return Ok(msg);
561 };
562
563 reader.consume(1);
564 }
565}
566
567#[cfg(feature = "tokio-1")]
570pub async fn read_v1_raw_message_async<M: Message, R: tokio::io::AsyncReadExt + Unpin>(
571 reader: &mut AsyncPeekReader<R>,
572) -> Result<MAVLinkV1MessageRaw, error::MessageReadError> {
573 loop {
574 loop {
575 if reader.read_u8().await? == MAV_STX {
577 break;
578 }
579 }
580
581 if let Some(message) = try_decode_v1_async::<M, _>(reader).await? {
582 return Ok(message);
583 }
584 }
585}
586
587#[cfg(feature = "embedded")]
593pub async fn read_v1_raw_message_async<M: Message>(
594 reader: &mut impl embedded_io_async::Read,
595) -> Result<MAVLinkV1MessageRaw, error::MessageReadError> {
596 loop {
597 let mut byte = [0u8];
599 loop {
600 reader
601 .read_exact(&mut byte)
602 .await
603 .map_err(|_| error::MessageReadError::Io)?;
604 if byte[0] == MAV_STX {
605 break;
606 }
607 }
608
609 let mut message = MAVLinkV1MessageRaw::new();
610
611 message.0[0] = MAV_STX;
612 reader
613 .read_exact(message.mut_header())
614 .await
615 .map_err(|_| error::MessageReadError::Io)?;
616 reader
617 .read_exact(message.mut_payload_and_checksum())
618 .await
619 .map_err(|_| error::MessageReadError::Io)?;
620
621 if message.has_valid_crc::<M>() {
624 return Ok(message);
625 }
626 }
627}
628
629pub fn read_v1_msg<M: Message, R: Read>(
631 r: &mut PeekReader<R>,
632) -> Result<(MavHeader, M), error::MessageReadError> {
633 let message = read_v1_raw_message::<M, _>(r)?;
634
635 Ok((
636 MavHeader {
637 sequence: message.sequence(),
638 system_id: message.system_id(),
639 component_id: message.component_id(),
640 },
641 M::parse(
642 MavlinkVersion::V1,
643 u32::from(message.message_id()),
644 message.payload(),
645 )?,
646 ))
647}
648
649#[cfg(feature = "tokio-1")]
651pub async fn read_v1_msg_async<M: Message, R: tokio::io::AsyncReadExt + Unpin>(
652 r: &mut AsyncPeekReader<R>,
653) -> Result<(MavHeader, M), error::MessageReadError> {
654 let message = read_v1_raw_message_async::<M, _>(r).await?;
655
656 Ok((
657 MavHeader {
658 sequence: message.sequence(),
659 system_id: message.system_id(),
660 component_id: message.component_id(),
661 },
662 M::parse(
663 MavlinkVersion::V1,
664 u32::from(message.message_id()),
665 message.payload(),
666 )?,
667 ))
668}
669
670#[cfg(feature = "embedded")]
675pub async fn read_v1_msg_async<M: Message>(
676 r: &mut impl embedded_io_async::Read,
677) -> Result<(MavHeader, M), error::MessageReadError> {
678 let message = read_v1_raw_message_async::<M>(r).await?;
679
680 Ok((
681 MavHeader {
682 sequence: message.sequence(),
683 system_id: message.system_id(),
684 component_id: message.component_id(),
685 },
686 M::parse(
687 MavlinkVersion::V1,
688 u32::from(message.message_id()),
689 message.payload(),
690 )?,
691 ))
692}
693
694const MAVLINK_IFLAG_SIGNED: u8 = 0x01;
695const MAVLINK_SUPPORTED_IFLAGS: u8 = MAVLINK_IFLAG_SIGNED;
696
697#[derive(Debug, Copy, Clone, PartialEq, Eq)]
698pub struct MAVLinkV2MessageRaw([u8; 1 + Self::HEADER_SIZE + 255 + 2 + Self::SIGNATURE_SIZE]);
703
704impl Default for MAVLinkV2MessageRaw {
705 fn default() -> Self {
706 Self::new()
707 }
708}
709
710impl MAVLinkV2MessageRaw {
711 const HEADER_SIZE: usize = 9;
712 const SIGNATURE_SIZE: usize = 13;
713
714 pub const fn new() -> Self {
715 Self([0; 1 + Self::HEADER_SIZE + 255 + 2 + Self::SIGNATURE_SIZE])
716 }
717
718 #[inline]
719 pub fn header(&self) -> &[u8] {
720 &self.0[1..=Self::HEADER_SIZE]
721 }
722
723 #[inline]
724 fn mut_header(&mut self) -> &mut [u8] {
725 &mut self.0[1..=Self::HEADER_SIZE]
726 }
727
728 #[inline]
729 pub fn payload_length(&self) -> u8 {
730 self.0[1]
731 }
732
733 #[inline]
734 pub fn incompatibility_flags(&self) -> u8 {
735 self.0[2]
736 }
737
738 #[inline]
739 pub fn incompatibility_flags_mut(&mut self) -> &mut u8 {
740 &mut self.0[2]
741 }
742
743 #[inline]
744 pub fn compatibility_flags(&self) -> u8 {
745 self.0[3]
746 }
747
748 #[inline]
749 pub fn sequence(&self) -> u8 {
750 self.0[4]
751 }
752
753 #[inline]
754 pub fn system_id(&self) -> u8 {
755 self.0[5]
756 }
757
758 #[inline]
759 pub fn component_id(&self) -> u8 {
760 self.0[6]
761 }
762
763 #[inline]
764 pub fn message_id(&self) -> u32 {
765 u32::from_le_bytes([self.0[7], self.0[8], self.0[9], 0])
766 }
767
768 #[inline]
769 pub fn payload(&self) -> &[u8] {
770 let payload_length: usize = self.payload_length().into();
771 &self.0[(1 + Self::HEADER_SIZE)..(1 + Self::HEADER_SIZE + payload_length)]
772 }
773
774 #[inline]
775 pub fn checksum(&self) -> u16 {
776 let payload_length: usize = self.payload_length().into();
777 u16::from_le_bytes([
778 self.0[1 + Self::HEADER_SIZE + payload_length],
779 self.0[1 + Self::HEADER_SIZE + payload_length + 1],
780 ])
781 }
782
783 #[cfg(feature = "signing")]
784 #[inline]
785 pub fn checksum_bytes(&self) -> &[u8] {
786 let checksum_offset = 1 + Self::HEADER_SIZE + self.payload_length() as usize;
787 &self.0[checksum_offset..(checksum_offset + 2)]
788 }
789
790 #[cfg(feature = "signing")]
791 #[inline]
792 pub fn signature_link_id(&self) -> u8 {
793 let payload_length: usize = self.payload_length().into();
794 self.0[1 + Self::HEADER_SIZE + payload_length + 2]
795 }
796
797 #[cfg(feature = "signing")]
798 #[inline]
799 pub fn signature_link_id_mut(&mut self) -> &mut u8 {
800 let payload_length: usize = self.payload_length().into();
801 &mut self.0[1 + Self::HEADER_SIZE + payload_length + 2]
802 }
803
804 #[cfg(feature = "signing")]
805 #[inline]
806 pub fn signature_timestamp_bytes(&self) -> &[u8] {
807 let payload_length: usize = self.payload_length().into();
808 let timestamp_start = 1 + Self::HEADER_SIZE + payload_length + 3;
809 &self.0[timestamp_start..(timestamp_start + 6)]
810 }
811
812 #[cfg(feature = "signing")]
813 #[inline]
814 pub fn signature_timestamp_bytes_mut(&mut self) -> &mut [u8] {
815 let payload_length: usize = self.payload_length().into();
816 let timestamp_start = 1 + Self::HEADER_SIZE + payload_length + 3;
817 &mut self.0[timestamp_start..(timestamp_start + 6)]
818 }
819
820 #[cfg(feature = "signing")]
821 #[inline]
822 pub fn signature_timestamp(&self) -> u64 {
823 let mut timestamp_bytes = [0u8; 8];
824 timestamp_bytes[0..6].copy_from_slice(self.signature_timestamp_bytes());
825 u64::from_le_bytes(timestamp_bytes)
826 }
827
828 #[cfg(feature = "signing")]
829 #[inline]
830 pub fn signature_value(&self) -> &[u8] {
831 let payload_length: usize = self.payload_length().into();
832 let signature_start = 1 + Self::HEADER_SIZE + payload_length + 3 + 6;
833 &self.0[signature_start..(signature_start + 6)]
834 }
835
836 #[cfg(feature = "signing")]
837 #[inline]
838 pub fn signature_value_mut(&mut self) -> &mut [u8] {
839 let payload_length: usize = self.payload_length().into();
840 let signature_start = 1 + Self::HEADER_SIZE + payload_length + 3 + 6;
841 &mut self.0[signature_start..(signature_start + 6)]
842 }
843
844 fn mut_payload_and_checksum_and_sign(&mut self) -> &mut [u8] {
845 let payload_length: usize = self.payload_length().into();
846
847 let signature_size = if (self.incompatibility_flags() & MAVLINK_IFLAG_SIGNED) == 0 {
849 0
850 } else {
851 Self::SIGNATURE_SIZE
852 };
853
854 &mut self.0
855 [(1 + Self::HEADER_SIZE)..(1 + Self::HEADER_SIZE + payload_length + signature_size + 2)]
856 }
857
858 #[inline]
859 pub fn has_valid_crc<M: Message>(&self) -> bool {
860 let payload_length: usize = self.payload_length().into();
861 self.checksum()
862 == calculate_crc(
863 &self.0[1..(1 + Self::HEADER_SIZE + payload_length)],
864 M::extra_crc(self.message_id()),
865 )
866 }
867
868 #[cfg(feature = "signing")]
869 pub fn calculate_signature(&self, secret_key: &[u8], target_buffer: &mut [u8; 6]) {
870 let mut hasher = Sha256::new();
871 hasher.update(secret_key);
872 hasher.update([MAV_STX_V2]);
873 hasher.update(self.header());
874 hasher.update(self.payload());
875 hasher.update(self.checksum_bytes());
876 hasher.update([self.signature_link_id()]);
877 hasher.update(self.signature_timestamp_bytes());
878 target_buffer.copy_from_slice(&hasher.finalize()[0..6]);
879 }
880
881 pub fn raw_bytes(&self) -> &[u8] {
882 let payload_length = self.payload_length() as usize;
883
884 let signature_size = if (self.incompatibility_flags() & MAVLINK_IFLAG_SIGNED) == 0 {
885 0
886 } else {
887 Self::SIGNATURE_SIZE
888 };
889
890 &self.0[..(1 + Self::HEADER_SIZE + payload_length + signature_size + 2)]
891 }
892
893 fn serialize_stx_and_header_and_crc(
894 &mut self,
895 header: MavHeader,
896 msgid: u32,
897 payload_length: usize,
898 extra_crc: u8,
899 incompat_flags: u8,
900 ) {
901 self.0[0] = MAV_STX_V2;
902 let msgid_bytes = msgid.to_le_bytes();
903
904 let header_buf = self.mut_header();
905 header_buf.copy_from_slice(&[
906 payload_length as u8,
907 incompat_flags,
908 0, header.sequence,
910 header.system_id,
911 header.component_id,
912 msgid_bytes[0],
913 msgid_bytes[1],
914 msgid_bytes[2],
915 ]);
916
917 let crc = calculate_crc(
918 &self.0[1..(1 + Self::HEADER_SIZE + payload_length)],
919 extra_crc,
920 );
921 self.0[(1 + Self::HEADER_SIZE + payload_length)
922 ..(1 + Self::HEADER_SIZE + payload_length + 2)]
923 .copy_from_slice(&crc.to_le_bytes());
924 }
925
926 pub fn serialize_message<M: Message>(&mut self, header: MavHeader, message: &M) {
927 let payload_buf = &mut self.0[(1 + Self::HEADER_SIZE)..(1 + Self::HEADER_SIZE + 255)];
928 let payload_length = message.ser(MavlinkVersion::V2, payload_buf);
929
930 let message_id = message.message_id();
931 self.serialize_stx_and_header_and_crc(
932 header,
933 message_id,
934 payload_length,
935 M::extra_crc(message_id),
936 0,
937 );
938 }
939
940 pub fn serialize_message_for_signing<M: Message>(&mut self, header: MavHeader, message: &M) {
941 let payload_buf = &mut self.0[(1 + Self::HEADER_SIZE)..(1 + Self::HEADER_SIZE + 255)];
942 let payload_length = message.ser(MavlinkVersion::V2, payload_buf);
943
944 let message_id = message.message_id();
945 self.serialize_stx_and_header_and_crc(
946 header,
947 message_id,
948 payload_length,
949 M::extra_crc(message_id),
950 0x01,
951 );
952 }
953
954 pub fn serialize_message_data<D: MessageData>(&mut self, header: MavHeader, message_data: &D) {
955 let payload_buf = &mut self.0[(1 + Self::HEADER_SIZE)..(1 + Self::HEADER_SIZE + 255)];
956 let payload_length = message_data.ser(MavlinkVersion::V2, payload_buf);
957
958 self.serialize_stx_and_header_and_crc(header, D::ID, payload_length, D::EXTRA_CRC, 0);
959 }
960}
961
962#[allow(unused_variables)]
963fn try_decode_v2<M: Message, R: Read>(
964 reader: &mut PeekReader<R>,
965 signing_data: Option<&SigningData>,
966) -> Result<Option<MAVLinkV2MessageRaw>, error::MessageReadError> {
967 let mut message = MAVLinkV2MessageRaw::new();
968 let whole_header_size = MAVLinkV2MessageRaw::HEADER_SIZE + 1;
969
970 message.0[0] = MAV_STX_V2;
971 let header = &reader.peek_exact(whole_header_size)?[1..whole_header_size];
972 message.mut_header().copy_from_slice(header);
973
974 if message.incompatibility_flags() & !MAVLINK_SUPPORTED_IFLAGS > 0 {
975 reader.consume(1);
977 return Ok(None);
978 }
979
980 let packet_length = message.raw_bytes().len();
981 let payload_and_checksum_and_sign =
982 &reader.peek_exact(packet_length)?[whole_header_size..packet_length];
983 message
984 .mut_payload_and_checksum_and_sign()
985 .copy_from_slice(payload_and_checksum_and_sign);
986
987 if message.has_valid_crc::<M>() {
988 reader.consume(message.raw_bytes().len());
990 } else {
991 reader.consume(1);
992 return Ok(None);
993 }
994
995 #[cfg(feature = "signing")]
996 if let Some(signing_data) = signing_data {
997 if !signing_data.verify_signature(&message) {
998 return Ok(None);
999 }
1000 }
1001
1002 Ok(Some(message))
1003}
1004
1005#[cfg(feature = "tokio-1")]
1006#[allow(unused_variables)]
1007async fn try_decode_v2_async<M: Message, R: tokio::io::AsyncReadExt + Unpin>(
1009 reader: &mut AsyncPeekReader<R>,
1010 signing_data: Option<&SigningData>,
1011) -> Result<Option<MAVLinkV2MessageRaw>, error::MessageReadError> {
1012 let mut message = MAVLinkV2MessageRaw::new();
1013
1014 message.0[0] = MAV_STX_V2;
1015 let header = &reader.peek_exact(MAVLinkV2MessageRaw::HEADER_SIZE).await?
1016 [..MAVLinkV2MessageRaw::HEADER_SIZE];
1017 message.mut_header().copy_from_slice(header);
1018
1019 if message.incompatibility_flags() & !MAVLINK_SUPPORTED_IFLAGS > 0 {
1020 return Ok(None);
1022 }
1023
1024 let packet_length = message.raw_bytes().len() - 1;
1025 let payload_and_checksum_and_sign =
1026 &reader.peek_exact(packet_length).await?[MAVLinkV2MessageRaw::HEADER_SIZE..packet_length];
1027 message
1028 .mut_payload_and_checksum_and_sign()
1029 .copy_from_slice(payload_and_checksum_and_sign);
1030
1031 if message.has_valid_crc::<M>() {
1032 reader.consume(message.raw_bytes().len() - 1);
1034 } else {
1035 return Ok(None);
1036 }
1037
1038 #[cfg(feature = "signing")]
1039 if let Some(signing_data) = signing_data {
1040 if !signing_data.verify_signature(&message) {
1041 return Ok(None);
1042 }
1043 }
1044
1045 Ok(Some(message))
1046}
1047
1048#[inline]
1052pub fn read_v2_raw_message<M: Message, R: Read>(
1053 reader: &mut PeekReader<R>,
1054) -> Result<MAVLinkV2MessageRaw, error::MessageReadError> {
1055 read_v2_raw_message_inner::<M, R>(reader, None)
1056}
1057
1058#[cfg(feature = "signing")]
1062#[inline]
1063pub fn read_v2_raw_message_signed<M: Message, R: Read>(
1064 reader: &mut PeekReader<R>,
1065 signing_data: Option<&SigningData>,
1066) -> Result<MAVLinkV2MessageRaw, error::MessageReadError> {
1067 read_v2_raw_message_inner::<M, R>(reader, signing_data)
1068}
1069
1070#[allow(unused_variables)]
1071fn read_v2_raw_message_inner<M: Message, R: Read>(
1072 reader: &mut PeekReader<R>,
1073 signing_data: Option<&SigningData>,
1074) -> Result<MAVLinkV2MessageRaw, error::MessageReadError> {
1075 loop {
1076 while reader.peek_exact(1)?[0] != MAV_STX_V2 {
1078 reader.consume(1);
1079 }
1080
1081 if let Some(message) = try_decode_v2::<M, _>(reader, signing_data)? {
1082 return Ok(message);
1083 }
1084 }
1085}
1086
1087#[cfg(feature = "tokio-1")]
1090pub async fn read_v2_raw_message_async<M: Message, R: tokio::io::AsyncReadExt + Unpin>(
1091 reader: &mut AsyncPeekReader<R>,
1092) -> Result<MAVLinkV2MessageRaw, error::MessageReadError> {
1093 read_v2_raw_message_async_inner::<M, R>(reader, None).await
1094}
1095
1096#[cfg(feature = "tokio-1")]
1099#[allow(unused_variables)]
1100async fn read_v2_raw_message_async_inner<M: Message, R: tokio::io::AsyncReadExt + Unpin>(
1101 reader: &mut AsyncPeekReader<R>,
1102 signing_data: Option<&SigningData>,
1103) -> Result<MAVLinkV2MessageRaw, error::MessageReadError> {
1104 loop {
1105 loop {
1106 if reader.read_u8().await? == MAV_STX_V2 {
1108 break;
1109 }
1110 }
1111
1112 if let Some(message) = try_decode_v2_async::<M, _>(reader, signing_data).await? {
1113 return Ok(message);
1114 }
1115 }
1116}
1117
1118#[cfg(all(feature = "tokio-1", feature = "signing"))]
1121pub async fn read_v2_raw_message_async_signed<M: Message, R: tokio::io::AsyncReadExt + Unpin>(
1122 reader: &mut AsyncPeekReader<R>,
1123 signing_data: Option<&SigningData>,
1124) -> Result<MAVLinkV2MessageRaw, error::MessageReadError> {
1125 read_v2_raw_message_async_inner::<M, R>(reader, signing_data).await
1126}
1127
1128#[cfg(feature = "embedded")]
1134pub async fn read_v2_raw_message_async<M: Message>(
1135 reader: &mut impl embedded_io_async::Read,
1136) -> Result<MAVLinkV2MessageRaw, error::MessageReadError> {
1137 loop {
1138 let mut byte = [0u8];
1140 loop {
1141 reader
1142 .read_exact(&mut byte)
1143 .await
1144 .map_err(|_| error::MessageReadError::Io)?;
1145 if byte[0] == MAV_STX_V2 {
1146 break;
1147 }
1148 }
1149
1150 let mut message = MAVLinkV2MessageRaw::new();
1151
1152 message.0[0] = MAV_STX_V2;
1153 reader
1154 .read_exact(message.mut_header())
1155 .await
1156 .map_err(|_| error::MessageReadError::Io)?;
1157
1158 if message.incompatibility_flags() & !MAVLINK_SUPPORTED_IFLAGS > 0 {
1159 continue;
1161 }
1162
1163 reader
1164 .read_exact(message.mut_payload_and_checksum_and_sign())
1165 .await
1166 .map_err(|_| error::MessageReadError::Io)?;
1167
1168 if message.has_valid_crc::<M>() {
1171 return Ok(message);
1172 }
1173 }
1174}
1175
1176#[inline]
1178pub fn read_v2_msg<M: Message, R: Read>(
1179 read: &mut PeekReader<R>,
1180) -> Result<(MavHeader, M), error::MessageReadError> {
1181 read_v2_msg_inner(read, None)
1182}
1183
1184#[cfg(feature = "signing")]
1186#[inline]
1187pub fn read_v2_msg_signed<M: Message, R: Read>(
1188 read: &mut PeekReader<R>,
1189 signing_data: Option<&SigningData>,
1190) -> Result<(MavHeader, M), error::MessageReadError> {
1191 read_v2_msg_inner(read, signing_data)
1192}
1193
1194fn read_v2_msg_inner<M: Message, R: Read>(
1195 read: &mut PeekReader<R>,
1196 signing_data: Option<&SigningData>,
1197) -> Result<(MavHeader, M), error::MessageReadError> {
1198 let message = read_v2_raw_message_inner::<M, _>(read, signing_data)?;
1199
1200 Ok((
1201 MavHeader {
1202 sequence: message.sequence(),
1203 system_id: message.system_id(),
1204 component_id: message.component_id(),
1205 },
1206 M::parse(MavlinkVersion::V2, message.message_id(), message.payload())?,
1207 ))
1208}
1209
1210#[cfg(feature = "tokio-1")]
1212pub async fn read_v2_msg_async<M: Message, R: tokio::io::AsyncReadExt + Unpin>(
1213 read: &mut AsyncPeekReader<R>,
1214) -> Result<(MavHeader, M), error::MessageReadError> {
1215 read_v2_msg_async_inner(read, None).await
1216}
1217
1218#[cfg(all(feature = "tokio-1", feature = "signing"))]
1220pub async fn read_v2_msg_async_signed<M: Message, R: tokio::io::AsyncReadExt + Unpin>(
1221 read: &mut AsyncPeekReader<R>,
1222 signing_data: Option<&SigningData>,
1223) -> Result<(MavHeader, M), error::MessageReadError> {
1224 read_v2_msg_async_inner(read, signing_data).await
1225}
1226
1227#[cfg(feature = "tokio-1")]
1228async fn read_v2_msg_async_inner<M: Message, R: tokio::io::AsyncReadExt + Unpin>(
1229 read: &mut AsyncPeekReader<R>,
1230 signing_data: Option<&SigningData>,
1231) -> Result<(MavHeader, M), error::MessageReadError> {
1232 let message = read_v2_raw_message_async_inner::<M, _>(read, signing_data).await?;
1233
1234 Ok((
1235 MavHeader {
1236 sequence: message.sequence(),
1237 system_id: message.system_id(),
1238 component_id: message.component_id(),
1239 },
1240 M::parse(MavlinkVersion::V2, message.message_id(), message.payload())?,
1241 ))
1242}
1243
1244#[cfg(feature = "embedded")]
1249pub async fn read_v2_msg_async<M: Message, R: embedded_io_async::Read>(
1250 r: &mut R,
1251) -> Result<(MavHeader, M), error::MessageReadError> {
1252 let message = read_v2_raw_message_async::<M>(r).await?;
1253
1254 Ok((
1255 MavHeader {
1256 sequence: message.sequence(),
1257 system_id: message.system_id(),
1258 component_id: message.component_id(),
1259 },
1260 M::parse(
1261 MavlinkVersion::V2,
1262 u32::from(message.message_id()),
1263 message.payload(),
1264 )?,
1265 ))
1266}
1267
1268pub enum MAVLinkMessageRaw {
1270 V1(MAVLinkV1MessageRaw),
1271 V2(MAVLinkV2MessageRaw),
1272}
1273
1274impl MAVLinkMessageRaw {
1275 fn payload(&self) -> &[u8] {
1276 match self {
1277 Self::V1(msg) => msg.payload(),
1278 Self::V2(msg) => msg.payload(),
1279 }
1280 }
1281 fn sequence(&self) -> u8 {
1282 match self {
1283 Self::V1(msg) => msg.sequence(),
1284 Self::V2(msg) => msg.sequence(),
1285 }
1286 }
1287 fn system_id(&self) -> u8 {
1288 match self {
1289 Self::V1(msg) => msg.system_id(),
1290 Self::V2(msg) => msg.system_id(),
1291 }
1292 }
1293 fn component_id(&self) -> u8 {
1294 match self {
1295 Self::V1(msg) => msg.component_id(),
1296 Self::V2(msg) => msg.component_id(),
1297 }
1298 }
1299 fn message_id(&self) -> u32 {
1300 match self {
1301 Self::V1(msg) => u32::from(msg.message_id()),
1302 Self::V2(msg) => msg.message_id(),
1303 }
1304 }
1305 fn version(&self) -> MavlinkVersion {
1306 match self {
1307 Self::V1(_) => MavlinkVersion::V1,
1308 Self::V2(_) => MavlinkVersion::V2,
1309 }
1310 }
1311}
1312
1313#[inline]
1315pub fn read_any_raw_message<M: Message, R: Read>(
1316 reader: &mut PeekReader<R>,
1317) -> Result<MAVLinkMessageRaw, error::MessageReadError> {
1318 read_any_raw_message_inner::<M, R>(reader, None)
1319}
1320
1321#[cfg(feature = "signing")]
1323#[inline]
1324pub fn read_any_raw_message_signed<M: Message, R: Read>(
1325 reader: &mut PeekReader<R>,
1326 signing_data: Option<&SigningData>,
1327) -> Result<MAVLinkMessageRaw, error::MessageReadError> {
1328 read_any_raw_message_inner::<M, R>(reader, signing_data)
1329}
1330
1331#[allow(unused_variables)]
1332fn read_any_raw_message_inner<M: Message, R: Read>(
1333 reader: &mut PeekReader<R>,
1334 signing_data: Option<&SigningData>,
1335) -> Result<MAVLinkMessageRaw, error::MessageReadError> {
1336 loop {
1337 let version = loop {
1339 let byte = reader.peek_exact(1)?[0];
1340 if byte == MAV_STX {
1341 break MavlinkVersion::V1;
1342 }
1343 if byte == MAV_STX_V2 {
1344 break MavlinkVersion::V2;
1345 }
1346 reader.consume(1);
1347 };
1348 match version {
1349 MavlinkVersion::V1 => {
1350 if let Some(message) = try_decode_v1::<M, _>(reader)? {
1351 #[cfg(feature = "signing")]
1353 if let Some(signing) = signing_data {
1354 if signing.config.allow_unsigned {
1355 return Ok(MAVLinkMessageRaw::V1(message));
1356 }
1357 } else {
1358 return Ok(MAVLinkMessageRaw::V1(message));
1359 }
1360 #[cfg(not(feature = "signing"))]
1361 return Ok(MAVLinkMessageRaw::V1(message));
1362 }
1363
1364 reader.consume(1);
1365 }
1366 MavlinkVersion::V2 => {
1367 if let Some(message) = try_decode_v2::<M, _>(reader, signing_data)? {
1368 return Ok(MAVLinkMessageRaw::V2(message));
1369 }
1370 }
1371 }
1372 }
1373}
1374
1375#[cfg(feature = "tokio-1")]
1377pub async fn read_any_raw_message_async<M: Message, R: tokio::io::AsyncReadExt + Unpin>(
1378 reader: &mut AsyncPeekReader<R>,
1379) -> Result<MAVLinkMessageRaw, error::MessageReadError> {
1380 read_any_raw_message_async_inner::<M, R>(reader, None).await
1381}
1382
1383#[cfg(all(feature = "tokio-1", feature = "signing"))]
1385pub async fn read_any_raw_message_async_signed<M: Message, R: tokio::io::AsyncReadExt + Unpin>(
1386 reader: &mut AsyncPeekReader<R>,
1387 signing_data: Option<&SigningData>,
1388) -> Result<MAVLinkMessageRaw, error::MessageReadError> {
1389 read_any_raw_message_async_inner::<M, R>(reader, signing_data).await
1390}
1391
1392#[cfg(feature = "tokio-1")]
1393#[allow(unused_variables)]
1394async fn read_any_raw_message_async_inner<M: Message, R: tokio::io::AsyncReadExt + Unpin>(
1395 reader: &mut AsyncPeekReader<R>,
1396 signing_data: Option<&SigningData>,
1397) -> Result<MAVLinkMessageRaw, error::MessageReadError> {
1398 loop {
1399 let version = loop {
1401 let read = reader.read_u8().await?;
1402 if read == MAV_STX {
1403 break MavlinkVersion::V1;
1404 }
1405 if read == MAV_STX_V2 {
1406 break MavlinkVersion::V2;
1407 }
1408 };
1409
1410 match version {
1411 MavlinkVersion::V1 => {
1412 if let Some(message) = try_decode_v1_async::<M, _>(reader).await? {
1413 #[cfg(feature = "signing")]
1415 if let Some(signing) = signing_data {
1416 if signing.config.allow_unsigned {
1417 return Ok(MAVLinkMessageRaw::V1(message));
1418 }
1419 } else {
1420 return Ok(MAVLinkMessageRaw::V1(message));
1421 }
1422 #[cfg(not(feature = "signing"))]
1423 return Ok(MAVLinkMessageRaw::V1(message));
1424 }
1425 }
1426 MavlinkVersion::V2 => {
1427 if let Some(message) = try_decode_v2_async::<M, _>(reader, signing_data).await? {
1428 return Ok(MAVLinkMessageRaw::V2(message));
1429 }
1430 }
1431 }
1432 }
1433}
1434
1435#[inline]
1437pub fn read_any_msg<M: Message, R: Read>(
1438 read: &mut PeekReader<R>,
1439) -> Result<(MavHeader, M), error::MessageReadError> {
1440 read_any_msg_inner(read, None)
1441}
1442
1443#[cfg(feature = "signing")]
1445#[inline]
1446pub fn read_any_msg_signed<M: Message, R: Read>(
1447 read: &mut PeekReader<R>,
1448 signing_data: Option<&SigningData>,
1449) -> Result<(MavHeader, M), error::MessageReadError> {
1450 read_any_msg_inner(read, signing_data)
1451}
1452
1453fn read_any_msg_inner<M: Message, R: Read>(
1454 read: &mut PeekReader<R>,
1455 signing_data: Option<&SigningData>,
1456) -> Result<(MavHeader, M), error::MessageReadError> {
1457 let message = read_any_raw_message_inner::<M, _>(read, signing_data)?;
1458 Ok((
1459 MavHeader {
1460 sequence: message.sequence(),
1461 system_id: message.system_id(),
1462 component_id: message.component_id(),
1463 },
1464 M::parse(message.version(), message.message_id(), message.payload())?,
1465 ))
1466}
1467
1468#[cfg(feature = "tokio-1")]
1470pub async fn read_any_msg_async<M: Message, R: tokio::io::AsyncReadExt + Unpin>(
1471 read: &mut AsyncPeekReader<R>,
1472) -> Result<(MavHeader, M), error::MessageReadError> {
1473 read_any_msg_async_inner(read, None).await
1474}
1475
1476#[cfg(all(feature = "tokio-1", feature = "signing"))]
1478#[inline]
1479pub async fn read_any_msg_async_signed<M: Message, R: tokio::io::AsyncReadExt + Unpin>(
1480 read: &mut AsyncPeekReader<R>,
1481 signing_data: Option<&SigningData>,
1482) -> Result<(MavHeader, M), error::MessageReadError> {
1483 read_any_msg_async_inner(read, signing_data).await
1484}
1485
1486#[cfg(feature = "tokio-1")]
1487async fn read_any_msg_async_inner<M: Message, R: tokio::io::AsyncReadExt + Unpin>(
1488 read: &mut AsyncPeekReader<R>,
1489 signing_data: Option<&SigningData>,
1490) -> Result<(MavHeader, M), error::MessageReadError> {
1491 let message = read_any_raw_message_async_inner::<M, _>(read, signing_data).await?;
1492
1493 Ok((
1494 MavHeader {
1495 sequence: message.sequence(),
1496 system_id: message.system_id(),
1497 component_id: message.component_id(),
1498 },
1499 M::parse(message.version(), message.message_id(), message.payload())?,
1500 ))
1501}
1502
1503pub fn write_versioned_msg<M: Message, W: Write>(
1505 w: &mut W,
1506 version: MavlinkVersion,
1507 header: MavHeader,
1508 data: &M,
1509) -> Result<usize, error::MessageWriteError> {
1510 match version {
1511 MavlinkVersion::V2 => write_v2_msg(w, header, data),
1512 MavlinkVersion::V1 => write_v1_msg(w, header, data),
1513 }
1514}
1515
1516#[cfg(feature = "signing")]
1518pub fn write_versioned_msg_signed<M: Message, W: Write>(
1519 w: &mut W,
1520 version: MavlinkVersion,
1521 header: MavHeader,
1522 data: &M,
1523 signing_data: Option<&SigningData>,
1524) -> Result<usize, error::MessageWriteError> {
1525 match version {
1526 MavlinkVersion::V2 => write_v2_msg_signed(w, header, data, signing_data),
1527 MavlinkVersion::V1 => write_v1_msg(w, header, data),
1528 }
1529}
1530
1531#[cfg(feature = "tokio-1")]
1533pub async fn write_versioned_msg_async<M: Message, W: tokio::io::AsyncWriteExt + Unpin>(
1534 w: &mut W,
1535 version: MavlinkVersion,
1536 header: MavHeader,
1537 data: &M,
1538) -> Result<usize, error::MessageWriteError> {
1539 match version {
1540 MavlinkVersion::V2 => write_v2_msg_async(w, header, data).await,
1541 MavlinkVersion::V1 => write_v1_msg_async(w, header, data).await,
1542 }
1543}
1544
1545#[cfg(all(feature = "tokio-1", feature = "signing"))]
1547pub async fn write_versioned_msg_async_signed<M: Message, W: tokio::io::AsyncWriteExt + Unpin>(
1548 w: &mut W,
1549 version: MavlinkVersion,
1550 header: MavHeader,
1551 data: &M,
1552 signing_data: Option<&SigningData>,
1553) -> Result<usize, error::MessageWriteError> {
1554 match version {
1555 MavlinkVersion::V2 => write_v2_msg_async_signed(w, header, data, signing_data).await,
1556 MavlinkVersion::V1 => write_v1_msg_async(w, header, data).await,
1557 }
1558}
1559
1560#[cfg(feature = "embedded")]
1565pub async fn write_versioned_msg_async<M: Message>(
1566 w: &mut impl embedded_io_async::Write,
1567 version: MavlinkVersion,
1568 header: MavHeader,
1569 data: &M,
1570) -> Result<usize, error::MessageWriteError> {
1571 match version {
1572 MavlinkVersion::V2 => write_v2_msg_async(w, header, data).await,
1573 MavlinkVersion::V1 => write_v1_msg_async(w, header, data).await,
1574 }
1575}
1576
1577pub fn write_v2_msg<M: Message, W: Write>(
1579 w: &mut W,
1580 header: MavHeader,
1581 data: &M,
1582) -> Result<usize, error::MessageWriteError> {
1583 let mut message_raw = MAVLinkV2MessageRaw::new();
1584 message_raw.serialize_message(header, data);
1585
1586 let payload_length: usize = message_raw.payload_length().into();
1587 let len = 1 + MAVLinkV2MessageRaw::HEADER_SIZE + payload_length + 2;
1588
1589 w.write_all(&message_raw.0[..len])?;
1590
1591 Ok(len)
1592}
1593
1594#[cfg(feature = "signing")]
1596pub fn write_v2_msg_signed<M: Message, W: Write>(
1597 w: &mut W,
1598 header: MavHeader,
1599 data: &M,
1600 signing_data: Option<&SigningData>,
1601) -> Result<usize, error::MessageWriteError> {
1602 let mut message_raw = MAVLinkV2MessageRaw::new();
1603
1604 let signature_len = if let Some(signing_data) = signing_data {
1605 if signing_data.config.sign_outgoing {
1606 message_raw.serialize_message_for_signing(header, data);
1607 signing_data.sign_message(&mut message_raw);
1608 MAVLinkV2MessageRaw::SIGNATURE_SIZE
1609 } else {
1610 message_raw.serialize_message(header, data);
1611 0
1612 }
1613 } else {
1614 message_raw.serialize_message(header, data);
1615 0
1616 };
1617
1618 let payload_length: usize = message_raw.payload_length().into();
1619 let len = 1 + MAVLinkV2MessageRaw::HEADER_SIZE + payload_length + 2 + signature_len;
1620
1621 w.write_all(&message_raw.0[..len])?;
1622
1623 Ok(len)
1624}
1625
1626#[cfg(feature = "tokio-1")]
1628pub async fn write_v2_msg_async<M: Message, W: tokio::io::AsyncWriteExt + Unpin>(
1629 w: &mut W,
1630 header: MavHeader,
1631 data: &M,
1632) -> Result<usize, error::MessageWriteError> {
1633 let mut message_raw = MAVLinkV2MessageRaw::new();
1634 message_raw.serialize_message(header, data);
1635
1636 let payload_length: usize = message_raw.payload_length().into();
1637 let len = 1 + MAVLinkV2MessageRaw::HEADER_SIZE + payload_length + 2;
1638
1639 w.write_all(&message_raw.0[..len]).await?;
1640
1641 Ok(len)
1642}
1643
1644#[cfg(feature = "signing")]
1646#[cfg(feature = "tokio-1")]
1647pub async fn write_v2_msg_async_signed<M: Message, W: tokio::io::AsyncWriteExt + Unpin>(
1648 w: &mut W,
1649 header: MavHeader,
1650 data: &M,
1651 signing_data: Option<&SigningData>,
1652) -> Result<usize, error::MessageWriteError> {
1653 let mut message_raw = MAVLinkV2MessageRaw::new();
1654
1655 let signature_len = if let Some(signing_data) = signing_data {
1656 if signing_data.config.sign_outgoing {
1657 message_raw.serialize_message_for_signing(header, data);
1658 signing_data.sign_message(&mut message_raw);
1659 MAVLinkV2MessageRaw::SIGNATURE_SIZE
1660 } else {
1661 message_raw.serialize_message(header, data);
1662 0
1663 }
1664 } else {
1665 message_raw.serialize_message(header, data);
1666 0
1667 };
1668
1669 let payload_length: usize = message_raw.payload_length().into();
1670 let len = 1 + MAVLinkV2MessageRaw::HEADER_SIZE + payload_length + 2 + signature_len;
1671
1672 w.write_all(&message_raw.0[..len]).await?;
1673
1674 Ok(len)
1675}
1676
1677#[cfg(feature = "embedded")]
1682pub async fn write_v2_msg_async<M: Message>(
1683 w: &mut impl embedded_io_async::Write,
1684 header: MavHeader,
1685 data: &M,
1686) -> Result<usize, error::MessageWriteError> {
1687 let mut message_raw = MAVLinkV2MessageRaw::new();
1688 message_raw.serialize_message(header, data);
1689
1690 let payload_length: usize = message_raw.payload_length().into();
1691 let len = 1 + MAVLinkV2MessageRaw::HEADER_SIZE + payload_length + 2;
1692
1693 w.write_all(&message_raw.0[..len])
1694 .await
1695 .map_err(|_| error::MessageWriteError::Io)?;
1696
1697 Ok(len)
1698}
1699
1700pub fn write_v1_msg<M: Message, W: Write>(
1702 w: &mut W,
1703 header: MavHeader,
1704 data: &M,
1705) -> Result<usize, error::MessageWriteError> {
1706 let mut message_raw = MAVLinkV1MessageRaw::new();
1707 message_raw.serialize_message(header, data);
1708
1709 let payload_length: usize = message_raw.payload_length().into();
1710 let len = 1 + MAVLinkV1MessageRaw::HEADER_SIZE + payload_length + 2;
1711
1712 w.write_all(&message_raw.0[..len])?;
1713
1714 Ok(len)
1715}
1716
1717#[cfg(feature = "tokio-1")]
1719pub async fn write_v1_msg_async<M: Message, W: tokio::io::AsyncWriteExt + Unpin>(
1720 w: &mut W,
1721 header: MavHeader,
1722 data: &M,
1723) -> Result<usize, error::MessageWriteError> {
1724 let mut message_raw = MAVLinkV1MessageRaw::new();
1725 message_raw.serialize_message(header, data);
1726
1727 let payload_length: usize = message_raw.payload_length().into();
1728 let len = 1 + MAVLinkV1MessageRaw::HEADER_SIZE + payload_length + 2;
1729
1730 w.write_all(&message_raw.0[..len]).await?;
1731
1732 Ok(len)
1733}
1734
1735#[cfg(feature = "embedded")]
1740pub async fn write_v1_msg_async<M: Message>(
1741 w: &mut impl embedded_io_async::Write,
1742 header: MavHeader,
1743 data: &M,
1744) -> Result<usize, error::MessageWriteError> {
1745 let mut message_raw = MAVLinkV1MessageRaw::new();
1746 message_raw.serialize_message(header, data);
1747
1748 let payload_length: usize = message_raw.payload_length().into();
1749 let len = 1 + MAVLinkV1MessageRaw::HEADER_SIZE + payload_length + 2;
1750
1751 w.write_all(&message_raw.0[..len])
1752 .await
1753 .map_err(|_| error::MessageWriteError::Io)?;
1754
1755 Ok(len)
1756}