1#![cfg_attr(not(feature = "std"), no_std)]
83#![cfg_attr(docsrs, feature(doc_cfg))]
84#![deny(clippy::all)]
85#![warn(clippy::use_self)]
86
87use core::result::Result;
88
89#[cfg(feature = "std")]
90use std::io::{Read, Write};
91
92pub mod utils;
93#[allow(unused_imports)]
94use utils::{RustDefault, remove_trailing_zeroes};
95
96#[cfg(feature = "serde")]
97use serde::{Deserialize, Serialize};
98
99pub mod peek_reader;
100use peek_reader::PeekReader;
101
102use crate::{
103 bytes::Bytes,
104 error::{MessageReadError, MessageWriteError, ParserError},
105};
106
107use crc_any::CRCu16;
108
109#[doc(hidden)]
110pub mod bytes;
111#[doc(hidden)]
112pub mod bytes_mut;
113#[cfg(feature = "std")]
114mod connection;
115pub mod error;
116pub mod types;
117#[cfg(feature = "std")]
118pub use self::connection::{Connectable, Connection, MavConnection, connect};
119
120#[cfg(feature = "tokio")]
121mod async_connection;
122#[cfg(feature = "tokio")]
123pub use self::async_connection::{AsyncConnectable, AsyncMavConnection, connect_async};
124
125#[cfg(feature = "tokio")]
126pub mod async_peek_reader;
127#[cfg(feature = "tokio")]
128use async_peek_reader::AsyncPeekReader;
129#[cfg(feature = "tokio")]
130use tokio::io::{AsyncWrite, AsyncWriteExt};
131
132#[cfg(all(feature = "embedded", not(feature = "std")))]
133pub mod embedded;
134#[cfg(all(feature = "embedded", not(feature = "std")))]
135use embedded::{Read, Write};
136
137#[cfg(not(feature = "mav2-message-signing"))]
138type SigningData = ();
139#[cfg(feature = "mav2-message-signing")]
140mod signing;
141#[cfg(feature = "mav2-message-signing")]
142pub use self::signing::{SigningConfig, SigningData};
143#[cfg(feature = "mav2-message-signing")]
144use sha2::{Digest, Sha256};
145
146#[cfg(feature = "arbitrary")]
147use arbitrary::Arbitrary;
148
149#[cfg(any(feature = "std", feature = "tokio"))]
150mod connectable;
151
152#[cfg(any(feature = "std", feature = "tokio"))]
153pub use connectable::ConnectionAddress;
154
155#[cfg(feature = "transport-direct-serial")]
156pub use connection::direct_serial::config::SerialConfig;
157
158#[cfg(feature = "transport-tcp")]
159pub use connection::tcp::config::{TcpConfig, TcpMode};
160
161#[cfg(feature = "transport-udp")]
162pub use connection::udp::config::{UdpConfig, UdpMode};
163
164#[cfg(feature = "std")]
165pub use connection::file::config::FileConfig;
166
167pub const MAX_FRAME_SIZE: usize = 280;
171
172pub trait Message
177where
178 Self: Sized,
179{
180 fn message_id(&self) -> u32;
182
183 fn message_name(&self) -> &'static str;
185
186 fn target_system_id(&self) -> Option<u8>;
188
189 fn target_component_id(&self) -> Option<u8>;
191
192 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize;
198
199 fn parse(version: MavlinkVersion, msgid: u32, payload: &[u8]) -> Result<Self, ParserError>;
208
209 fn message_id_from_name(name: &str) -> Option<u32>;
211 fn default_message_from_id(id: u32) -> Option<Self>;
213 #[cfg(feature = "arbitrary")]
215 fn random_message_from_id<R: rand::RngCore>(id: u32, rng: &mut R) -> Option<Self>;
216 fn extra_crc(id: u32) -> u8;
218}
219
220pub trait MessageData: Sized {
221 type Message: Message;
222
223 const ID: u32;
224 const NAME: &'static str;
225 const EXTRA_CRC: u8;
226 const ENCODED_LEN: usize;
227
228 fn ser(&self, version: MavlinkVersion, payload: &mut [u8]) -> usize;
232 fn deser(version: MavlinkVersion, payload: &[u8]) -> Result<Self, ParserError>;
237}
238
239#[derive(Debug, Copy, Clone, PartialEq, Eq)]
241#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
242#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
243pub struct MavHeader {
244 pub system_id: u8,
246 pub component_id: u8,
248 pub sequence: u8,
250}
251
252#[derive(Debug, Copy, Clone, PartialEq, Eq)]
254#[cfg_attr(feature = "serde", derive(Serialize))]
255#[cfg_attr(feature = "serde", serde(tag = "type"))]
256#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
257pub enum MavlinkVersion {
258 V1,
260 V2,
262}
263
264pub const MAV_STX: u8 = 0xFE;
266
267pub const MAV_STX_V2: u8 = 0xFD;
269
270impl Default for MavHeader {
273 fn default() -> Self {
274 Self {
275 system_id: 255,
276 component_id: 0,
277 sequence: 0,
278 }
279 }
280}
281
282#[derive(Debug, Clone)]
286#[cfg_attr(feature = "serde", derive(Serialize))]
287#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
288pub struct MavFrame<M: Message> {
289 pub header: MavHeader,
291 pub msg: M,
293 pub protocol_version: MavlinkVersion,
295}
296
297impl<M: Message> MavFrame<M> {
298 pub fn ser(&self, buf: &mut [u8]) -> usize {
307 let mut buf = bytes_mut::BytesMut::new(buf);
308
309 let mut payload_buf = [0u8; 255];
311 let payload_len = self.msg.ser(self.protocol_version, &mut payload_buf);
312
313 buf.put_u8(self.header.sequence);
332 buf.put_u8(self.header.system_id);
333 buf.put_u8(self.header.component_id);
334
335 match self.protocol_version {
337 MavlinkVersion::V2 => {
338 let bytes: [u8; 4] = self.msg.message_id().to_le_bytes();
339 buf.put_slice(&bytes[..3]);
340 }
341 MavlinkVersion::V1 => {
342 buf.put_u8(
343 self.msg
344 .message_id()
345 .try_into()
346 .expect("message is MAVLink 2 only"),
347 );
348 }
349 }
350
351 buf.put_slice(&payload_buf[..payload_len]);
352 buf.len()
353 }
354
355 pub fn deser(version: MavlinkVersion, input: &[u8]) -> Result<Self, ParserError> {
364 let mut buf = Bytes::new(input);
365
366 let sequence = buf.get_u8()?;
376 let system_id = buf.get_u8()?;
377 let component_id = buf.get_u8()?;
378 let header = MavHeader {
379 system_id,
380 component_id,
381 sequence,
382 };
383
384 let msg_id = match version {
385 MavlinkVersion::V2 => buf.get_u24_le()?,
386 MavlinkVersion::V1 => buf.get_u8()?.into(),
387 };
388
389 M::parse(version, msg_id, buf.remaining_bytes()).map(|msg| Self {
390 header,
391 msg,
392 protocol_version: version,
393 })
394 }
395
396 pub fn header(&self) -> MavHeader {
398 self.header
399 }
400}
401
402pub fn calculate_crc(data: &[u8], extra_crc: u8) -> u16 {
404 let mut crc_calculator = CRCu16::crc16mcrf4cc();
405 crc_calculator.digest(data);
406
407 crc_calculator.digest(&[extra_crc]);
408 crc_calculator.get_crc()
409}
410
411#[derive(Debug, Clone, Copy, PartialEq, Eq)]
412pub enum ReadVersion {
414 Single(MavlinkVersion),
416 Any,
418}
419
420impl ReadVersion {
421 #[cfg(feature = "std")]
422 fn from_conn_cfg<C: MavConnection<M>, M: Message>(conn: &C) -> Self {
423 if conn.allow_recv_any_version() {
424 Self::Any
425 } else {
426 conn.protocol_version().into()
427 }
428 }
429 #[cfg(feature = "tokio")]
430 fn from_async_conn_cfg<C: AsyncMavConnection<M>, M: Message + Sync + Send>(conn: &C) -> Self {
431 if conn.allow_recv_any_version() {
432 Self::Any
433 } else {
434 conn.protocol_version().into()
435 }
436 }
437}
438
439impl From<MavlinkVersion> for ReadVersion {
440 fn from(value: MavlinkVersion) -> Self {
441 Self::Single(value)
442 }
443}
444
445pub fn read_versioned_msg<M: Message, R: Read>(
451 r: &mut PeekReader<R>,
452 version: ReadVersion,
453) -> Result<(MavHeader, M), MessageReadError> {
454 match version {
455 ReadVersion::Single(MavlinkVersion::V2) => read_v2_msg(r),
456 ReadVersion::Single(MavlinkVersion::V1) => read_v1_msg(r),
457 ReadVersion::Any => read_any_msg(r),
458 }
459}
460
461pub fn read_versioned_raw_message<M: Message, R: Read>(
467 r: &mut PeekReader<R>,
468 version: ReadVersion,
469) -> Result<MAVLinkMessageRaw, MessageReadError> {
470 match version {
471 ReadVersion::Single(MavlinkVersion::V2) => {
472 Ok(MAVLinkMessageRaw::V2(read_v2_raw_message::<M, _>(r)?))
473 }
474 ReadVersion::Single(MavlinkVersion::V1) => {
475 Ok(MAVLinkMessageRaw::V1(read_v1_raw_message::<M, _>(r)?))
476 }
477 ReadVersion::Any => read_any_raw_message::<M, _>(r),
478 }
479}
480
481#[cfg(feature = "tokio")]
487pub async fn read_versioned_msg_async<M: Message, R: tokio::io::AsyncRead + Unpin>(
488 r: &mut AsyncPeekReader<R>,
489 version: ReadVersion,
490) -> Result<(MavHeader, M), MessageReadError> {
491 match version {
492 ReadVersion::Single(MavlinkVersion::V2) => read_v2_msg_async(r).await,
493 ReadVersion::Single(MavlinkVersion::V1) => read_v1_msg_async(r).await,
494 ReadVersion::Any => read_any_msg_async(r).await,
495 }
496}
497
498#[cfg(feature = "tokio")]
504pub async fn read_versioned_raw_message_async<M: Message, R: tokio::io::AsyncRead + Unpin>(
505 r: &mut AsyncPeekReader<R>,
506 version: ReadVersion,
507) -> Result<MAVLinkMessageRaw, MessageReadError> {
508 match version {
509 ReadVersion::Single(MavlinkVersion::V2) => Ok(MAVLinkMessageRaw::V2(
510 read_v2_raw_message_async::<M, _>(r).await?,
511 )),
512 ReadVersion::Single(MavlinkVersion::V1) => Ok(MAVLinkMessageRaw::V1(
513 read_v1_raw_message_async::<M, _>(r).await?,
514 )),
515 ReadVersion::Any => read_any_raw_message_async::<M, _>(r).await,
516 }
517}
518
519#[cfg(feature = "mav2-message-signing")]
528pub fn read_versioned_raw_message_signed<M: Message, R: Read>(
529 r: &mut PeekReader<R>,
530 version: ReadVersion,
531 signing_data: Option<&SigningData>,
532) -> Result<MAVLinkMessageRaw, MessageReadError> {
533 match version {
534 ReadVersion::Single(MavlinkVersion::V2) => Ok(MAVLinkMessageRaw::V2(
535 read_v2_raw_message_inner::<M, _>(r, signing_data)?,
536 )),
537 ReadVersion::Single(MavlinkVersion::V1) => {
538 Ok(MAVLinkMessageRaw::V1(read_v1_raw_message::<M, _>(r)?))
539 }
540 ReadVersion::Any => read_any_raw_message_inner::<M, _>(r, signing_data),
541 }
542}
543
544#[cfg(feature = "mav2-message-signing")]
553pub fn read_versioned_msg_signed<M: Message, R: Read>(
554 r: &mut PeekReader<R>,
555 version: ReadVersion,
556 signing_data: Option<&SigningData>,
557) -> Result<(MavHeader, M), MessageReadError> {
558 match version {
559 ReadVersion::Single(MavlinkVersion::V2) => read_v2_msg_inner(r, signing_data),
560 ReadVersion::Single(MavlinkVersion::V1) => read_v1_msg(r),
561 ReadVersion::Any => read_any_msg_inner(r, signing_data),
562 }
563}
564
565#[cfg(all(feature = "tokio", feature = "mav2-message-signing"))]
574pub async fn read_versioned_raw_message_async_signed<
575 M: Message,
576 R: tokio::io::AsyncRead + Unpin,
577>(
578 r: &mut AsyncPeekReader<R>,
579 version: ReadVersion,
580 signing_data: Option<&SigningData>,
581) -> Result<MAVLinkMessageRaw, MessageReadError> {
582 match version {
583 ReadVersion::Single(MavlinkVersion::V2) => Ok(MAVLinkMessageRaw::V2(
584 read_v2_raw_message_async_inner::<M, _>(r, signing_data).await?,
585 )),
586 ReadVersion::Single(MavlinkVersion::V1) => Ok(MAVLinkMessageRaw::V1(
587 read_v1_raw_message_async::<M, _>(r).await?,
588 )),
589 ReadVersion::Any => read_any_raw_message_async_inner::<M, _>(r, signing_data).await,
590 }
591}
592
593#[cfg(all(feature = "tokio", feature = "mav2-message-signing"))]
602pub async fn read_versioned_msg_async_signed<M: Message, R: tokio::io::AsyncRead + Unpin>(
603 r: &mut AsyncPeekReader<R>,
604 version: ReadVersion,
605 signing_data: Option<&SigningData>,
606) -> Result<(MavHeader, M), MessageReadError> {
607 match version {
608 ReadVersion::Single(MavlinkVersion::V2) => read_v2_msg_async_inner(r, signing_data).await,
609 ReadVersion::Single(MavlinkVersion::V1) => read_v1_msg_async(r).await,
610 ReadVersion::Any => read_any_msg_async_inner(r, signing_data).await,
611 }
612}
613
614#[derive(Debug, Copy, Clone, PartialEq, Eq)]
615pub struct MAVLinkV1MessageRaw([u8; 1 + Self::HEADER_SIZE + 255 + 2]);
620
621impl Default for MAVLinkV1MessageRaw {
622 fn default() -> Self {
623 Self::new()
624 }
625}
626
627impl MAVLinkV1MessageRaw {
628 const HEADER_SIZE: usize = 5;
629
630 pub const fn new() -> Self {
632 Self([0; 1 + Self::HEADER_SIZE + 255 + 2])
633 }
634
635 pub const fn from_bytes_unparsed(bytes: [u8; 1 + Self::HEADER_SIZE + 255 + 2]) -> Self {
639 Self(bytes)
640 }
641
642 #[inline]
644 pub fn as_slice(&self) -> &[u8] {
645 &self.0
646 }
647
648 #[inline]
650 pub fn as_mut_slice(&mut self) -> &mut [u8] {
651 &mut self.0
652 }
653
654 #[inline]
656 pub fn into_inner(self) -> [u8; 1 + Self::HEADER_SIZE + 255 + 2] {
657 self.0
658 }
659
660 #[inline]
662 pub fn header(&self) -> &[u8] {
663 &self.0[1..=Self::HEADER_SIZE]
664 }
665
666 #[inline]
668 fn mut_header(&mut self) -> &mut [u8] {
669 &mut self.0[1..=Self::HEADER_SIZE]
670 }
671
672 #[inline]
674 pub fn payload_length(&self) -> u8 {
675 self.0[1]
676 }
677
678 #[inline]
680 pub fn sequence(&self) -> u8 {
681 self.0[2]
682 }
683
684 #[inline]
686 pub fn system_id(&self) -> u8 {
687 self.0[3]
688 }
689
690 #[inline]
692 pub fn component_id(&self) -> u8 {
693 self.0[4]
694 }
695
696 #[inline]
698 pub fn message_id(&self) -> u8 {
699 self.0[5]
700 }
701
702 #[inline]
704 pub fn payload(&self) -> &[u8] {
705 let payload_length: usize = self.payload_length().into();
706 &self.0[(1 + Self::HEADER_SIZE)..(1 + Self::HEADER_SIZE + payload_length)]
707 }
708
709 #[inline]
711 pub fn checksum(&self) -> u16 {
712 let payload_length: usize = self.payload_length().into();
713 u16::from_le_bytes([
714 self.0[1 + Self::HEADER_SIZE + payload_length],
715 self.0[1 + Self::HEADER_SIZE + payload_length + 1],
716 ])
717 }
718
719 #[inline]
720 fn mut_payload_and_checksum(&mut self) -> &mut [u8] {
721 let payload_length: usize = self.payload_length().into();
722 &mut self.0[(1 + Self::HEADER_SIZE)..(1 + Self::HEADER_SIZE + payload_length + 2)]
723 }
724
725 #[inline]
727 pub fn has_valid_crc<M: Message>(&self) -> bool {
728 let payload_length: usize = self.payload_length().into();
729 self.checksum()
730 == calculate_crc(
731 &self.0[1..(1 + Self::HEADER_SIZE + payload_length)],
732 M::extra_crc(self.message_id().into()),
733 )
734 }
735
736 pub fn raw_bytes(&self) -> &[u8] {
738 let payload_length = self.payload_length() as usize;
739 &self.0[..(1 + Self::HEADER_SIZE + payload_length + 2)]
740 }
741
742 fn serialize_stx_and_header_and_crc(
746 &mut self,
747 header: MavHeader,
748 msgid: u32,
749 payload_length: usize,
750 extra_crc: u8,
751 ) {
752 self.0[0] = MAV_STX;
753
754 let header_buf = self.mut_header();
755 header_buf.copy_from_slice(&[
756 payload_length as u8,
757 header.sequence,
758 header.system_id,
759 header.component_id,
760 msgid.try_into().unwrap(),
761 ]);
762
763 let crc = calculate_crc(
764 &self.0[1..(1 + Self::HEADER_SIZE + payload_length)],
765 extra_crc,
766 );
767 self.0[(1 + Self::HEADER_SIZE + payload_length)
768 ..(1 + Self::HEADER_SIZE + payload_length + 2)]
769 .copy_from_slice(&crc.to_le_bytes());
770 }
771
772 pub fn serialize_message<M: Message>(&mut self, header: MavHeader, message: &M) {
778 let payload_buf = &mut self.0[(1 + Self::HEADER_SIZE)..(1 + Self::HEADER_SIZE + 255)];
779 let payload_length = message.ser(MavlinkVersion::V1, payload_buf);
780
781 let message_id = message.message_id();
782 self.serialize_stx_and_header_and_crc(
783 header,
784 message_id,
785 payload_length,
786 M::extra_crc(message_id),
787 );
788 }
789
790 pub fn serialize_message_data<D: MessageData>(&mut self, header: MavHeader, message_data: &D) {
794 let payload_buf = &mut self.0[(1 + Self::HEADER_SIZE)..(1 + Self::HEADER_SIZE + 255)];
795 let payload_length = message_data.ser(MavlinkVersion::V1, payload_buf);
796
797 self.serialize_stx_and_header_and_crc(header, D::ID, payload_length, D::EXTRA_CRC);
798 }
799}
800
801fn try_decode_v1<M: Message, R: Read>(
802 reader: &mut PeekReader<R>,
803) -> Result<Option<MAVLinkV1MessageRaw>, MessageReadError> {
804 let mut message = MAVLinkV1MessageRaw::new();
805 let whole_header_size = MAVLinkV1MessageRaw::HEADER_SIZE + 1;
806
807 message.0[0] = MAV_STX;
808 let header = &reader.peek_exact(whole_header_size)?[1..whole_header_size];
809 message.mut_header().copy_from_slice(header);
810 let packet_length = message.raw_bytes().len();
811 let payload_and_checksum = &reader.peek_exact(packet_length)?[whole_header_size..packet_length];
812 message
813 .mut_payload_and_checksum()
814 .copy_from_slice(payload_and_checksum);
815
816 if message.has_valid_crc::<M>() {
819 reader.consume(message.raw_bytes().len());
820 Ok(Some(message))
821 } else {
822 Ok(None)
823 }
824}
825
826#[cfg(feature = "tokio")]
827async fn try_decode_v1_async<M: Message, R: tokio::io::AsyncRead + Unpin>(
829 reader: &mut AsyncPeekReader<R>,
830) -> Result<Option<MAVLinkV1MessageRaw>, MessageReadError> {
831 let mut message = MAVLinkV1MessageRaw::new();
832
833 message.0[0] = MAV_STX;
834 let header = &reader.peek_exact(MAVLinkV1MessageRaw::HEADER_SIZE).await?
835 [..MAVLinkV1MessageRaw::HEADER_SIZE];
836 message.mut_header().copy_from_slice(header);
837 let packet_length = message.raw_bytes().len() - 1;
838 let payload_and_checksum =
839 &reader.peek_exact(packet_length).await?[MAVLinkV1MessageRaw::HEADER_SIZE..packet_length];
840 message
841 .mut_payload_and_checksum()
842 .copy_from_slice(payload_and_checksum);
843
844 if message.has_valid_crc::<M>() {
847 reader.consume(message.raw_bytes().len() - 1);
848 Ok(Some(message))
849 } else {
850 Ok(None)
851 }
852}
853
854pub fn read_v1_raw_message<M: Message, R: Read>(
860 reader: &mut PeekReader<R>,
861) -> Result<MAVLinkV1MessageRaw, MessageReadError> {
862 loop {
863 while reader.peek_exact(1)?[0] != MAV_STX {
865 reader.consume(1);
866 }
867
868 if let Some(msg) = try_decode_v1::<M, _>(reader)? {
869 return Ok(msg);
870 }
871
872 reader.consume(1);
873 }
874}
875
876#[cfg(feature = "tokio")]
882pub async fn read_v1_raw_message_async<M: Message, R: tokio::io::AsyncRead + Unpin>(
883 reader: &mut AsyncPeekReader<R>,
884) -> Result<MAVLinkV1MessageRaw, MessageReadError> {
885 loop {
886 loop {
887 if reader.read_u8().await? == MAV_STX {
889 break;
890 }
891 }
892
893 if let Some(message) = try_decode_v1_async::<M, _>(reader).await? {
894 return Ok(message);
895 }
896 }
897}
898
899#[cfg(all(feature = "embedded", not(feature = "std")))]
906pub async fn read_v1_raw_message_async<M: Message>(
907 reader: &mut impl embedded_io_async::Read,
908) -> Result<MAVLinkV1MessageRaw, MessageReadError> {
909 loop {
910 let mut byte = [0u8];
912 loop {
913 reader
914 .read_exact(&mut byte)
915 .await
916 .map_err(|_| MessageReadError::Io)?;
917 if byte[0] == MAV_STX {
918 break;
919 }
920 }
921
922 let mut message = MAVLinkV1MessageRaw::new();
923
924 message.0[0] = MAV_STX;
925 reader
926 .read_exact(message.mut_header())
927 .await
928 .map_err(|_| MessageReadError::Io)?;
929 reader
930 .read_exact(message.mut_payload_and_checksum())
931 .await
932 .map_err(|_| MessageReadError::Io)?;
933
934 if message.has_valid_crc::<M>() {
937 return Ok(message);
938 }
939 }
940}
941
942pub fn read_v1_msg<M: Message, R: Read>(
948 r: &mut PeekReader<R>,
949) -> Result<(MavHeader, M), MessageReadError> {
950 let message = read_v1_raw_message::<M, _>(r)?;
951
952 Ok((
953 MavHeader {
954 sequence: message.sequence(),
955 system_id: message.system_id(),
956 component_id: message.component_id(),
957 },
958 M::parse(
959 MavlinkVersion::V1,
960 u32::from(message.message_id()),
961 message.payload(),
962 )?,
963 ))
964}
965
966#[cfg(feature = "tokio")]
972pub async fn read_v1_msg_async<M: Message, R: tokio::io::AsyncRead + Unpin>(
973 r: &mut AsyncPeekReader<R>,
974) -> Result<(MavHeader, M), MessageReadError> {
975 let message = read_v1_raw_message_async::<M, _>(r).await?;
976
977 Ok((
978 MavHeader {
979 sequence: message.sequence(),
980 system_id: message.system_id(),
981 component_id: message.component_id(),
982 },
983 M::parse(
984 MavlinkVersion::V1,
985 u32::from(message.message_id()),
986 message.payload(),
987 )?,
988 ))
989}
990
991#[cfg(all(feature = "embedded", not(feature = "std")))]
996pub async fn read_v1_msg_async<M: Message>(
997 r: &mut impl embedded_io_async::Read,
998) -> Result<(MavHeader, M), MessageReadError> {
999 let message = read_v1_raw_message_async::<M>(r).await?;
1000
1001 Ok((
1002 MavHeader {
1003 sequence: message.sequence(),
1004 system_id: message.system_id(),
1005 component_id: message.component_id(),
1006 },
1007 M::parse(
1008 MavlinkVersion::V1,
1009 u32::from(message.message_id()),
1010 message.payload(),
1011 )?,
1012 ))
1013}
1014
1015const MAVLINK_IFLAG_SIGNED: u8 = 0x01;
1016const MAVLINK_SUPPORTED_IFLAGS: u8 = MAVLINK_IFLAG_SIGNED;
1017
1018#[derive(Debug, Copy, Clone, PartialEq, Eq)]
1019pub struct MAVLinkV2MessageRaw([u8; 1 + Self::HEADER_SIZE + 255 + 2 + Self::SIGNATURE_SIZE]);
1024
1025impl Default for MAVLinkV2MessageRaw {
1026 fn default() -> Self {
1027 Self::new()
1028 }
1029}
1030
1031impl MAVLinkV2MessageRaw {
1032 const HEADER_SIZE: usize = 9;
1033 const SIGNATURE_SIZE: usize = 13;
1034
1035 pub const fn new() -> Self {
1037 Self([0; 1 + Self::HEADER_SIZE + 255 + 2 + Self::SIGNATURE_SIZE])
1038 }
1039
1040 pub const fn from_bytes_unparsed(
1044 bytes: [u8; 1 + Self::HEADER_SIZE + 255 + 2 + Self::SIGNATURE_SIZE],
1045 ) -> Self {
1046 Self(bytes)
1047 }
1048
1049 #[inline]
1051 pub fn as_slice(&self) -> &[u8] {
1052 &self.0
1053 }
1054
1055 #[inline]
1057 pub fn as_mut_slice(&mut self) -> &mut [u8] {
1058 &mut self.0
1059 }
1060
1061 #[inline]
1063 pub fn into_inner(self) -> [u8; 1 + Self::HEADER_SIZE + 255 + 2 + Self::SIGNATURE_SIZE] {
1064 self.0
1065 }
1066
1067 #[inline]
1069 pub fn header(&self) -> &[u8] {
1070 &self.0[1..=Self::HEADER_SIZE]
1071 }
1072
1073 #[inline]
1075 fn mut_header(&mut self) -> &mut [u8] {
1076 &mut self.0[1..=Self::HEADER_SIZE]
1077 }
1078
1079 #[inline]
1081 pub fn payload_length(&self) -> u8 {
1082 self.0[1]
1083 }
1084
1085 #[inline]
1089 pub fn incompatibility_flags(&self) -> u8 {
1090 self.0[2]
1091 }
1092
1093 #[inline]
1097 pub fn incompatibility_flags_mut(&mut self) -> &mut u8 {
1098 &mut self.0[2]
1099 }
1100
1101 #[inline]
1103 pub fn compatibility_flags(&self) -> u8 {
1104 self.0[3]
1105 }
1106
1107 #[inline]
1109 pub fn sequence(&self) -> u8 {
1110 self.0[4]
1111 }
1112
1113 #[inline]
1115 pub fn system_id(&self) -> u8 {
1116 self.0[5]
1117 }
1118
1119 #[inline]
1121 pub fn component_id(&self) -> u8 {
1122 self.0[6]
1123 }
1124
1125 #[inline]
1127 pub fn message_id(&self) -> u32 {
1128 u32::from_le_bytes([self.0[7], self.0[8], self.0[9], 0])
1129 }
1130
1131 #[inline]
1133 pub fn payload(&self) -> &[u8] {
1134 let payload_length: usize = self.payload_length().into();
1135 &self.0[(1 + Self::HEADER_SIZE)..(1 + Self::HEADER_SIZE + payload_length)]
1136 }
1137
1138 #[inline]
1140 pub fn checksum(&self) -> u16 {
1141 let payload_length: usize = self.payload_length().into();
1142 u16::from_le_bytes([
1143 self.0[1 + Self::HEADER_SIZE + payload_length],
1144 self.0[1 + Self::HEADER_SIZE + payload_length + 1],
1145 ])
1146 }
1147
1148 #[cfg(feature = "mav2-message-signing")]
1150 #[inline]
1151 pub fn checksum_bytes(&self) -> &[u8] {
1152 let checksum_offset = 1 + Self::HEADER_SIZE + self.payload_length() as usize;
1153 &self.0[checksum_offset..(checksum_offset + 2)]
1154 }
1155
1156 #[cfg(feature = "mav2-message-signing")]
1160 #[inline]
1161 pub fn signature_link_id(&self) -> u8 {
1162 let payload_length: usize = self.payload_length().into();
1163 self.0[1 + Self::HEADER_SIZE + payload_length + 2]
1164 }
1165
1166 #[cfg(feature = "mav2-message-signing")]
1168 #[inline]
1169 pub fn signature_link_id_mut(&mut self) -> &mut u8 {
1170 let payload_length: usize = self.payload_length().into();
1171 &mut self.0[1 + Self::HEADER_SIZE + payload_length + 2]
1172 }
1173
1174 #[cfg(feature = "mav2-message-signing")]
1180 #[inline]
1181 pub fn signature_timestamp(&self) -> u64 {
1182 let mut timestamp_bytes = [0u8; 8];
1183 timestamp_bytes[0..6].copy_from_slice(self.signature_timestamp_bytes());
1184 u64::from_le_bytes(timestamp_bytes)
1185 }
1186
1187 #[cfg(feature = "mav2-message-signing")]
1191 #[inline]
1192 pub fn signature_timestamp_bytes(&self) -> &[u8] {
1193 let payload_length: usize = self.payload_length().into();
1194 let timestamp_start = 1 + Self::HEADER_SIZE + payload_length + 3;
1195 &self.0[timestamp_start..(timestamp_start + 6)]
1196 }
1197
1198 #[cfg(feature = "mav2-message-signing")]
1200 #[inline]
1201 pub fn signature_timestamp_bytes_mut(&mut self) -> &mut [u8] {
1202 let payload_length: usize = self.payload_length().into();
1203 let timestamp_start = 1 + Self::HEADER_SIZE + payload_length + 3;
1204 &mut self.0[timestamp_start..(timestamp_start + 6)]
1205 }
1206
1207 #[cfg(feature = "mav2-message-signing")]
1211 #[inline]
1212 pub fn signature_value(&self) -> &[u8] {
1213 let payload_length: usize = self.payload_length().into();
1214 let signature_start = 1 + Self::HEADER_SIZE + payload_length + 3 + 6;
1215 &self.0[signature_start..(signature_start + 6)]
1216 }
1217
1218 #[cfg(feature = "mav2-message-signing")]
1220 #[inline]
1221 pub fn signature_value_mut(&mut self) -> &mut [u8] {
1222 let payload_length: usize = self.payload_length().into();
1223 let signature_start = 1 + Self::HEADER_SIZE + payload_length + 3 + 6;
1224 &mut self.0[signature_start..(signature_start + 6)]
1225 }
1226
1227 fn mut_payload_and_checksum_and_sign(&mut self) -> &mut [u8] {
1228 let payload_length: usize = self.payload_length().into();
1229
1230 let signature_size = if (self.incompatibility_flags() & MAVLINK_IFLAG_SIGNED) == 0 {
1232 0
1233 } else {
1234 Self::SIGNATURE_SIZE
1235 };
1236
1237 &mut self.0
1238 [(1 + Self::HEADER_SIZE)..(1 + Self::HEADER_SIZE + payload_length + signature_size + 2)]
1239 }
1240
1241 #[inline]
1243 pub fn has_valid_crc<M: Message>(&self) -> bool {
1244 let payload_length: usize = self.payload_length().into();
1245 self.checksum()
1246 == calculate_crc(
1247 &self.0[1..(1 + Self::HEADER_SIZE + payload_length)],
1248 M::extra_crc(self.message_id()),
1249 )
1250 }
1251
1252 #[cfg(feature = "mav2-message-signing")]
1256 pub fn calculate_signature(&self, secret_key: &[u8], target_buffer: &mut [u8; 6]) {
1257 let mut hasher = Sha256::new();
1258 hasher.update(secret_key);
1259 hasher.update([MAV_STX_V2]);
1260 hasher.update(self.header());
1261 hasher.update(self.payload());
1262 hasher.update(self.checksum_bytes());
1263 hasher.update([self.signature_link_id()]);
1264 hasher.update(self.signature_timestamp_bytes());
1265 target_buffer.copy_from_slice(&hasher.finalize()[0..6]);
1266 }
1267
1268 pub fn raw_bytes(&self) -> &[u8] {
1270 let payload_length = self.payload_length() as usize;
1271
1272 let signature_size = if (self.incompatibility_flags() & MAVLINK_IFLAG_SIGNED) == 0 {
1273 0
1274 } else {
1275 Self::SIGNATURE_SIZE
1276 };
1277
1278 &self.0[..(1 + Self::HEADER_SIZE + payload_length + signature_size + 2)]
1279 }
1280
1281 fn serialize_stx_and_header_and_crc(
1282 &mut self,
1283 header: MavHeader,
1284 msgid: u32,
1285 payload_length: usize,
1286 extra_crc: u8,
1287 incompat_flags: u8,
1288 ) {
1289 self.0[0] = MAV_STX_V2;
1290 let msgid_bytes = msgid.to_le_bytes();
1291
1292 let header_buf = self.mut_header();
1293 header_buf.copy_from_slice(&[
1294 payload_length as u8,
1295 incompat_flags,
1296 0, header.sequence,
1298 header.system_id,
1299 header.component_id,
1300 msgid_bytes[0],
1301 msgid_bytes[1],
1302 msgid_bytes[2],
1303 ]);
1304
1305 let crc = calculate_crc(
1306 &self.0[1..(1 + Self::HEADER_SIZE + payload_length)],
1307 extra_crc,
1308 );
1309 self.0[(1 + Self::HEADER_SIZE + payload_length)
1310 ..(1 + Self::HEADER_SIZE + payload_length + 2)]
1311 .copy_from_slice(&crc.to_le_bytes());
1312 }
1313
1314 pub fn serialize_message<M: Message>(&mut self, header: MavHeader, message: &M) {
1318 let payload_buf = &mut self.0[(1 + Self::HEADER_SIZE)..(1 + Self::HEADER_SIZE + 255)];
1319 let payload_length = message.ser(MavlinkVersion::V2, payload_buf);
1320
1321 let message_id = message.message_id();
1322 self.serialize_stx_and_header_and_crc(
1323 header,
1324 message_id,
1325 payload_length,
1326 M::extra_crc(message_id),
1327 0,
1328 );
1329 }
1330
1331 pub fn serialize_message_for_signing<M: Message>(&mut self, header: MavHeader, message: &M) {
1336 let payload_buf = &mut self.0[(1 + Self::HEADER_SIZE)..(1 + Self::HEADER_SIZE + 255)];
1337 let payload_length = message.ser(MavlinkVersion::V2, payload_buf);
1338
1339 let message_id = message.message_id();
1340 self.serialize_stx_and_header_and_crc(
1341 header,
1342 message_id,
1343 payload_length,
1344 M::extra_crc(message_id),
1345 MAVLINK_IFLAG_SIGNED,
1346 );
1347 }
1348
1349 pub fn serialize_message_data<D: MessageData>(&mut self, header: MavHeader, message_data: &D) {
1350 let payload_buf = &mut self.0[(1 + Self::HEADER_SIZE)..(1 + Self::HEADER_SIZE + 255)];
1351 let payload_length = message_data.ser(MavlinkVersion::V2, payload_buf);
1352
1353 self.serialize_stx_and_header_and_crc(header, D::ID, payload_length, D::EXTRA_CRC, 0);
1354 }
1355}
1356
1357#[allow(unused_variables)]
1358fn try_decode_v2<M: Message, R: Read>(
1359 reader: &mut PeekReader<R>,
1360 signing_data: Option<&SigningData>,
1361) -> Result<Option<MAVLinkV2MessageRaw>, MessageReadError> {
1362 let mut message = MAVLinkV2MessageRaw::new();
1363 let whole_header_size = MAVLinkV2MessageRaw::HEADER_SIZE + 1;
1364
1365 message.0[0] = MAV_STX_V2;
1366 let header = &reader.peek_exact(whole_header_size)?[1..whole_header_size];
1367 message.mut_header().copy_from_slice(header);
1368
1369 if message.incompatibility_flags() & !MAVLINK_SUPPORTED_IFLAGS > 0 {
1370 reader.consume(1);
1372 return Ok(None);
1373 }
1374
1375 let packet_length = message.raw_bytes().len();
1376 let payload_and_checksum_and_sign =
1377 &reader.peek_exact(packet_length)?[whole_header_size..packet_length];
1378 message
1379 .mut_payload_and_checksum_and_sign()
1380 .copy_from_slice(payload_and_checksum_and_sign);
1381
1382 if message.has_valid_crc::<M>() {
1383 reader.consume(message.raw_bytes().len());
1385 } else {
1386 reader.consume(1);
1387 return Ok(None);
1388 }
1389
1390 #[cfg(feature = "mav2-message-signing")]
1391 if let Some(signing_data) = signing_data {
1392 if !signing_data.verify_signature(&message) {
1393 return Ok(None);
1394 }
1395 }
1396
1397 Ok(Some(message))
1398}
1399
1400#[cfg(feature = "tokio")]
1401#[allow(unused_variables)]
1402async fn try_decode_v2_async<M: Message, R: tokio::io::AsyncRead + Unpin>(
1404 reader: &mut AsyncPeekReader<R>,
1405 signing_data: Option<&SigningData>,
1406) -> Result<Option<MAVLinkV2MessageRaw>, MessageReadError> {
1407 let mut message = MAVLinkV2MessageRaw::new();
1408
1409 message.0[0] = MAV_STX_V2;
1410 let header = &reader.peek_exact(MAVLinkV2MessageRaw::HEADER_SIZE).await?
1411 [..MAVLinkV2MessageRaw::HEADER_SIZE];
1412 message.mut_header().copy_from_slice(header);
1413
1414 if message.incompatibility_flags() & !MAVLINK_SUPPORTED_IFLAGS > 0 {
1415 return Ok(None);
1417 }
1418
1419 let packet_length = message.raw_bytes().len() - 1;
1420 let payload_and_checksum_and_sign =
1421 &reader.peek_exact(packet_length).await?[MAVLinkV2MessageRaw::HEADER_SIZE..packet_length];
1422 message
1423 .mut_payload_and_checksum_and_sign()
1424 .copy_from_slice(payload_and_checksum_and_sign);
1425
1426 if message.has_valid_crc::<M>() {
1427 reader.consume(message.raw_bytes().len() - 1);
1429 } else {
1430 return Ok(None);
1431 }
1432
1433 #[cfg(feature = "mav2-message-signing")]
1434 if let Some(signing_data) = signing_data {
1435 if !signing_data.verify_signature(&message) {
1436 return Ok(None);
1437 }
1438 }
1439
1440 Ok(Some(message))
1441}
1442
1443#[inline]
1449pub fn read_v2_raw_message<M: Message, R: Read>(
1450 reader: &mut PeekReader<R>,
1451) -> Result<MAVLinkV2MessageRaw, MessageReadError> {
1452 read_v2_raw_message_inner::<M, R>(reader, None)
1453}
1454
1455#[cfg(feature = "mav2-message-signing")]
1461#[inline]
1462pub fn read_v2_raw_message_signed<M: Message, R: Read>(
1463 reader: &mut PeekReader<R>,
1464 signing_data: Option<&SigningData>,
1465) -> Result<MAVLinkV2MessageRaw, MessageReadError> {
1466 read_v2_raw_message_inner::<M, R>(reader, signing_data)
1467}
1468
1469#[allow(unused_variables)]
1470fn read_v2_raw_message_inner<M: Message, R: Read>(
1471 reader: &mut PeekReader<R>,
1472 signing_data: Option<&SigningData>,
1473) -> Result<MAVLinkV2MessageRaw, MessageReadError> {
1474 loop {
1475 while reader.peek_exact(1)?[0] != MAV_STX_V2 {
1477 reader.consume(1);
1478 }
1479
1480 if let Some(message) = try_decode_v2::<M, _>(reader, signing_data)? {
1481 return Ok(message);
1482 }
1483 }
1484}
1485
1486#[cfg(feature = "tokio")]
1492pub async fn read_v2_raw_message_async<M: Message, R: tokio::io::AsyncRead + Unpin>(
1493 reader: &mut AsyncPeekReader<R>,
1494) -> Result<MAVLinkV2MessageRaw, MessageReadError> {
1495 read_v2_raw_message_async_inner::<M, R>(reader, None).await
1496}
1497
1498#[cfg(feature = "tokio")]
1499#[allow(unused_variables)]
1500async fn read_v2_raw_message_async_inner<M: Message, R: tokio::io::AsyncRead + Unpin>(
1501 reader: &mut AsyncPeekReader<R>,
1502 signing_data: Option<&SigningData>,
1503) -> Result<MAVLinkV2MessageRaw, MessageReadError> {
1504 loop {
1505 loop {
1506 if reader.read_u8().await? == MAV_STX_V2 {
1508 break;
1509 }
1510 }
1511
1512 if let Some(message) = try_decode_v2_async::<M, _>(reader, signing_data).await? {
1513 return Ok(message);
1514 }
1515 }
1516}
1517
1518#[cfg(all(feature = "tokio", feature = "mav2-message-signing"))]
1524pub async fn read_v2_raw_message_async_signed<M: Message, R: tokio::io::AsyncRead + Unpin>(
1525 reader: &mut AsyncPeekReader<R>,
1526 signing_data: Option<&SigningData>,
1527) -> Result<MAVLinkV2MessageRaw, MessageReadError> {
1528 read_v2_raw_message_async_inner::<M, R>(reader, signing_data).await
1529}
1530
1531#[cfg(all(feature = "embedded", not(feature = "std")))]
1537pub async fn read_v2_raw_message_async<M: Message>(
1538 reader: &mut impl embedded_io_async::Read,
1539) -> Result<MAVLinkV2MessageRaw, MessageReadError> {
1540 loop {
1541 let mut byte = [0u8];
1543 loop {
1544 reader
1545 .read_exact(&mut byte)
1546 .await
1547 .map_err(|_| MessageReadError::Io)?;
1548 if byte[0] == MAV_STX_V2 {
1549 break;
1550 }
1551 }
1552
1553 let mut message = MAVLinkV2MessageRaw::new();
1554
1555 message.0[0] = MAV_STX_V2;
1556 reader
1557 .read_exact(message.mut_header())
1558 .await
1559 .map_err(|_| MessageReadError::Io)?;
1560
1561 if message.incompatibility_flags() & !MAVLINK_SUPPORTED_IFLAGS > 0 {
1562 continue;
1564 }
1565
1566 reader
1567 .read_exact(message.mut_payload_and_checksum_and_sign())
1568 .await
1569 .map_err(|_| MessageReadError::Io)?;
1570
1571 if message.has_valid_crc::<M>() {
1574 return Ok(message);
1575 }
1576 }
1577}
1578
1579#[inline]
1585pub fn read_v2_msg<M: Message, R: Read>(
1586 read: &mut PeekReader<R>,
1587) -> Result<(MavHeader, M), MessageReadError> {
1588 read_v2_msg_inner(read, None)
1589}
1590
1591#[cfg(feature = "mav2-message-signing")]
1597#[inline]
1598pub fn read_v2_msg_signed<M: Message, R: Read>(
1599 read: &mut PeekReader<R>,
1600 signing_data: Option<&SigningData>,
1601) -> Result<(MavHeader, M), MessageReadError> {
1602 read_v2_msg_inner(read, signing_data)
1603}
1604
1605fn read_v2_msg_inner<M: Message, R: Read>(
1606 read: &mut PeekReader<R>,
1607 signing_data: Option<&SigningData>,
1608) -> Result<(MavHeader, M), MessageReadError> {
1609 let message = read_v2_raw_message_inner::<M, _>(read, signing_data)?;
1610
1611 Ok((
1612 MavHeader {
1613 sequence: message.sequence(),
1614 system_id: message.system_id(),
1615 component_id: message.component_id(),
1616 },
1617 M::parse(MavlinkVersion::V2, message.message_id(), message.payload())?,
1618 ))
1619}
1620
1621#[cfg(feature = "tokio")]
1627pub async fn read_v2_msg_async<M: Message, R: tokio::io::AsyncRead + Unpin>(
1628 read: &mut AsyncPeekReader<R>,
1629) -> Result<(MavHeader, M), MessageReadError> {
1630 read_v2_msg_async_inner(read, None).await
1631}
1632
1633#[cfg(all(feature = "tokio", feature = "mav2-message-signing"))]
1639pub async fn read_v2_msg_async_signed<M: Message, R: tokio::io::AsyncRead + Unpin>(
1640 read: &mut AsyncPeekReader<R>,
1641 signing_data: Option<&SigningData>,
1642) -> Result<(MavHeader, M), MessageReadError> {
1643 read_v2_msg_async_inner(read, signing_data).await
1644}
1645
1646#[cfg(feature = "tokio")]
1647async fn read_v2_msg_async_inner<M: Message, R: tokio::io::AsyncRead + Unpin>(
1648 read: &mut AsyncPeekReader<R>,
1649 signing_data: Option<&SigningData>,
1650) -> Result<(MavHeader, M), MessageReadError> {
1651 let message = read_v2_raw_message_async_inner::<M, _>(read, signing_data).await?;
1652
1653 Ok((
1654 MavHeader {
1655 sequence: message.sequence(),
1656 system_id: message.system_id(),
1657 component_id: message.component_id(),
1658 },
1659 M::parse(MavlinkVersion::V2, message.message_id(), message.payload())?,
1660 ))
1661}
1662
1663#[cfg(all(feature = "embedded", not(feature = "std")))]
1668pub async fn read_v2_msg_async<M: Message, R: embedded_io_async::Read>(
1669 r: &mut R,
1670) -> Result<(MavHeader, M), MessageReadError> {
1671 let message = read_v2_raw_message_async::<M>(r).await?;
1672
1673 Ok((
1674 MavHeader {
1675 sequence: message.sequence(),
1676 system_id: message.system_id(),
1677 component_id: message.component_id(),
1678 },
1679 M::parse(
1680 MavlinkVersion::V2,
1681 u32::from(message.message_id()),
1682 message.payload(),
1683 )?,
1684 ))
1685}
1686
1687pub enum MAVLinkMessageRaw {
1689 V1(MAVLinkV1MessageRaw),
1690 V2(MAVLinkV2MessageRaw),
1691}
1692
1693impl MAVLinkMessageRaw {
1694 pub fn payload(&self) -> &[u8] {
1695 match self {
1696 Self::V1(msg) => msg.payload(),
1697 Self::V2(msg) => msg.payload(),
1698 }
1699 }
1700 pub fn sequence(&self) -> u8 {
1701 match self {
1702 Self::V1(msg) => msg.sequence(),
1703 Self::V2(msg) => msg.sequence(),
1704 }
1705 }
1706 pub fn system_id(&self) -> u8 {
1707 match self {
1708 Self::V1(msg) => msg.system_id(),
1709 Self::V2(msg) => msg.system_id(),
1710 }
1711 }
1712 pub fn component_id(&self) -> u8 {
1713 match self {
1714 Self::V1(msg) => msg.component_id(),
1715 Self::V2(msg) => msg.component_id(),
1716 }
1717 }
1718 pub fn message_id(&self) -> u32 {
1719 match self {
1720 Self::V1(msg) => u32::from(msg.message_id()),
1721 Self::V2(msg) => msg.message_id(),
1722 }
1723 }
1724 pub fn version(&self) -> MavlinkVersion {
1725 match self {
1726 Self::V1(_) => MavlinkVersion::V1,
1727 Self::V2(_) => MavlinkVersion::V2,
1728 }
1729 }
1730}
1731
1732#[inline]
1738pub fn read_any_raw_message<M: Message, R: Read>(
1739 reader: &mut PeekReader<R>,
1740) -> Result<MAVLinkMessageRaw, MessageReadError> {
1741 read_any_raw_message_inner::<M, R>(reader, None)
1742}
1743
1744#[cfg(feature = "mav2-message-signing")]
1750#[inline]
1751pub fn read_any_raw_message_signed<M: Message, R: Read>(
1752 reader: &mut PeekReader<R>,
1753 signing_data: Option<&SigningData>,
1754) -> Result<MAVLinkMessageRaw, MessageReadError> {
1755 read_any_raw_message_inner::<M, R>(reader, signing_data)
1756}
1757
1758#[allow(unused_variables)]
1759fn read_any_raw_message_inner<M: Message, R: Read>(
1760 reader: &mut PeekReader<R>,
1761 signing_data: Option<&SigningData>,
1762) -> Result<MAVLinkMessageRaw, MessageReadError> {
1763 loop {
1764 let version = loop {
1766 let byte = reader.peek_exact(1)?[0];
1767 if byte == MAV_STX {
1768 break MavlinkVersion::V1;
1769 }
1770 if byte == MAV_STX_V2 {
1771 break MavlinkVersion::V2;
1772 }
1773 reader.consume(1);
1774 };
1775 match version {
1776 MavlinkVersion::V1 => {
1777 if let Some(message) = try_decode_v1::<M, _>(reader)? {
1778 #[cfg(feature = "mav2-message-signing")]
1780 if let Some(signing) = signing_data {
1781 if signing.config.allow_unsigned {
1782 return Ok(MAVLinkMessageRaw::V1(message));
1783 }
1784 } else {
1785 return Ok(MAVLinkMessageRaw::V1(message));
1786 }
1787 #[cfg(not(feature = "mav2-message-signing"))]
1788 return Ok(MAVLinkMessageRaw::V1(message));
1789 }
1790
1791 reader.consume(1);
1792 }
1793 MavlinkVersion::V2 => {
1794 if let Some(message) = try_decode_v2::<M, _>(reader, signing_data)? {
1795 return Ok(MAVLinkMessageRaw::V2(message));
1796 }
1797 }
1798 }
1799 }
1800}
1801
1802#[cfg(feature = "tokio")]
1808pub async fn read_any_raw_message_async<M: Message, R: tokio::io::AsyncRead + Unpin>(
1809 reader: &mut AsyncPeekReader<R>,
1810) -> Result<MAVLinkMessageRaw, MessageReadError> {
1811 read_any_raw_message_async_inner::<M, R>(reader, None).await
1812}
1813
1814#[cfg(all(feature = "tokio", feature = "mav2-message-signing"))]
1822pub async fn read_any_raw_message_async_signed<M: Message, R: tokio::io::AsyncRead + Unpin>(
1823 reader: &mut AsyncPeekReader<R>,
1824 signing_data: Option<&SigningData>,
1825) -> Result<MAVLinkMessageRaw, MessageReadError> {
1826 read_any_raw_message_async_inner::<M, R>(reader, signing_data).await
1827}
1828
1829#[cfg(feature = "tokio")]
1830#[allow(unused_variables)]
1831async fn read_any_raw_message_async_inner<M: Message, R: tokio::io::AsyncRead + Unpin>(
1832 reader: &mut AsyncPeekReader<R>,
1833 signing_data: Option<&SigningData>,
1834) -> Result<MAVLinkMessageRaw, MessageReadError> {
1835 loop {
1836 let version = loop {
1838 let read = reader.read_u8().await?;
1839 if read == MAV_STX {
1840 break MavlinkVersion::V1;
1841 }
1842 if read == MAV_STX_V2 {
1843 break MavlinkVersion::V2;
1844 }
1845 };
1846
1847 match version {
1848 MavlinkVersion::V1 => {
1849 if let Some(message) = try_decode_v1_async::<M, _>(reader).await? {
1850 #[cfg(feature = "mav2-message-signing")]
1852 if let Some(signing) = signing_data {
1853 if signing.config.allow_unsigned {
1854 return Ok(MAVLinkMessageRaw::V1(message));
1855 }
1856 } else {
1857 return Ok(MAVLinkMessageRaw::V1(message));
1858 }
1859 #[cfg(not(feature = "mav2-message-signing"))]
1860 return Ok(MAVLinkMessageRaw::V1(message));
1861 }
1862 }
1863 MavlinkVersion::V2 => {
1864 if let Some(message) = try_decode_v2_async::<M, _>(reader, signing_data).await? {
1865 return Ok(MAVLinkMessageRaw::V2(message));
1866 }
1867 }
1868 }
1869 }
1870}
1871
1872#[inline]
1878pub fn read_any_msg<M: Message, R: Read>(
1879 read: &mut PeekReader<R>,
1880) -> Result<(MavHeader, M), MessageReadError> {
1881 read_any_msg_inner(read, None)
1882}
1883
1884#[cfg(feature = "mav2-message-signing")]
1892#[inline]
1893pub fn read_any_msg_signed<M: Message, R: Read>(
1894 read: &mut PeekReader<R>,
1895 signing_data: Option<&SigningData>,
1896) -> Result<(MavHeader, M), MessageReadError> {
1897 read_any_msg_inner(read, signing_data)
1898}
1899
1900fn read_any_msg_inner<M: Message, R: Read>(
1901 read: &mut PeekReader<R>,
1902 signing_data: Option<&SigningData>,
1903) -> Result<(MavHeader, M), MessageReadError> {
1904 let message = read_any_raw_message_inner::<M, _>(read, signing_data)?;
1905 Ok((
1906 MavHeader {
1907 sequence: message.sequence(),
1908 system_id: message.system_id(),
1909 component_id: message.component_id(),
1910 },
1911 M::parse(message.version(), message.message_id(), message.payload())?,
1912 ))
1913}
1914
1915#[cfg(feature = "tokio")]
1921pub async fn read_any_msg_async<M: Message, R: tokio::io::AsyncRead + Unpin>(
1922 read: &mut AsyncPeekReader<R>,
1923) -> Result<(MavHeader, M), MessageReadError> {
1924 read_any_msg_async_inner(read, None).await
1925}
1926
1927#[cfg(all(feature = "tokio", feature = "mav2-message-signing"))]
1935#[inline]
1936pub async fn read_any_msg_async_signed<M: Message, R: tokio::io::AsyncRead + Unpin>(
1937 read: &mut AsyncPeekReader<R>,
1938 signing_data: Option<&SigningData>,
1939) -> Result<(MavHeader, M), MessageReadError> {
1940 read_any_msg_async_inner(read, signing_data).await
1941}
1942
1943#[cfg(feature = "tokio")]
1944async fn read_any_msg_async_inner<M: Message, R: tokio::io::AsyncRead + Unpin>(
1945 read: &mut AsyncPeekReader<R>,
1946 signing_data: Option<&SigningData>,
1947) -> Result<(MavHeader, M), MessageReadError> {
1948 let message = read_any_raw_message_async_inner::<M, _>(read, signing_data).await?;
1949
1950 Ok((
1951 MavHeader {
1952 sequence: message.sequence(),
1953 system_id: message.system_id(),
1954 component_id: message.component_id(),
1955 },
1956 M::parse(message.version(), message.message_id(), message.payload())?,
1957 ))
1958}
1959
1960pub fn write_versioned_msg<M: Message, W: Write>(
1966 w: &mut W,
1967 version: MavlinkVersion,
1968 header: MavHeader,
1969 data: &M,
1970) -> Result<usize, MessageWriteError> {
1971 match version {
1972 MavlinkVersion::V2 => write_v2_msg(w, header, data),
1973 MavlinkVersion::V1 => write_v1_msg(w, header, data),
1974 }
1975}
1976
1977#[cfg(feature = "mav2-message-signing")]
1985pub fn write_versioned_msg_signed<M: Message, W: Write>(
1986 w: &mut W,
1987 version: MavlinkVersion,
1988 header: MavHeader,
1989 data: &M,
1990 signing_data: Option<&SigningData>,
1991) -> Result<usize, MessageWriteError> {
1992 match version {
1993 MavlinkVersion::V2 => write_v2_msg_signed(w, header, data, signing_data),
1994 MavlinkVersion::V1 => write_v1_msg(w, header, data),
1995 }
1996}
1997
1998#[cfg(feature = "tokio")]
2004pub async fn write_versioned_msg_async<M: Message, W: AsyncWrite + Unpin>(
2005 w: &mut W,
2006 version: MavlinkVersion,
2007 header: MavHeader,
2008 data: &M,
2009) -> Result<usize, MessageWriteError> {
2010 match version {
2011 MavlinkVersion::V2 => write_v2_msg_async(w, header, data).await,
2012 MavlinkVersion::V1 => write_v1_msg_async(w, header, data).await,
2013 }
2014}
2015
2016#[cfg(all(feature = "tokio", feature = "mav2-message-signing"))]
2024pub async fn write_versioned_msg_async_signed<M: Message, W: AsyncWrite + Unpin>(
2025 w: &mut W,
2026 version: MavlinkVersion,
2027 header: MavHeader,
2028 data: &M,
2029 signing_data: Option<&SigningData>,
2030) -> Result<usize, MessageWriteError> {
2031 match version {
2032 MavlinkVersion::V2 => write_v2_msg_async_signed(w, header, data, signing_data).await,
2033 MavlinkVersion::V1 => write_v1_msg_async(w, header, data).await,
2034 }
2035}
2036
2037#[cfg(all(feature = "embedded", not(feature = "std")))]
2042pub async fn write_versioned_msg_async<M: Message>(
2043 w: &mut impl embedded_io_async::Write,
2044 version: MavlinkVersion,
2045 header: MavHeader,
2046 data: &M,
2047) -> Result<usize, MessageWriteError> {
2048 match version {
2049 MavlinkVersion::V2 => write_v2_msg_async(w, header, data).await,
2050 MavlinkVersion::V1 => write_v1_msg_async(w, header, data).await,
2051 }
2052}
2053
2054pub fn write_v2_msg<M: Message, W: Write>(
2060 w: &mut W,
2061 header: MavHeader,
2062 data: &M,
2063) -> Result<usize, MessageWriteError> {
2064 let mut message_raw = MAVLinkV2MessageRaw::new();
2065 message_raw.serialize_message(header, data);
2066
2067 let payload_length: usize = message_raw.payload_length().into();
2068 let len = 1 + MAVLinkV2MessageRaw::HEADER_SIZE + payload_length + 2;
2069
2070 w.write_all(&message_raw.0[..len])?;
2071
2072 Ok(len)
2073}
2074
2075#[cfg(feature = "mav2-message-signing")]
2081pub fn write_v2_msg_signed<M: Message, W: Write>(
2082 w: &mut W,
2083 header: MavHeader,
2084 data: &M,
2085 signing_data: Option<&SigningData>,
2086) -> Result<usize, MessageWriteError> {
2087 let mut message_raw = MAVLinkV2MessageRaw::new();
2088
2089 let signature_len = if let Some(signing_data) = signing_data {
2090 if signing_data.config.sign_outgoing {
2091 message_raw.serialize_message_for_signing(header, data);
2092 signing_data.sign_message(&mut message_raw);
2093 MAVLinkV2MessageRaw::SIGNATURE_SIZE
2094 } else {
2095 message_raw.serialize_message(header, data);
2096 0
2097 }
2098 } else {
2099 message_raw.serialize_message(header, data);
2100 0
2101 };
2102
2103 let payload_length: usize = message_raw.payload_length().into();
2104 let len = 1 + MAVLinkV2MessageRaw::HEADER_SIZE + payload_length + 2 + signature_len;
2105
2106 w.write_all(&message_raw.0[..len])?;
2107
2108 Ok(len)
2109}
2110
2111#[cfg(feature = "tokio")]
2117pub async fn write_v2_msg_async<M: Message, W: AsyncWrite + Unpin>(
2118 w: &mut W,
2119 header: MavHeader,
2120 data: &M,
2121) -> Result<usize, MessageWriteError> {
2122 let mut message_raw = MAVLinkV2MessageRaw::new();
2123 message_raw.serialize_message(header, data);
2124
2125 let payload_length: usize = message_raw.payload_length().into();
2126 let len = 1 + MAVLinkV2MessageRaw::HEADER_SIZE + payload_length + 2;
2127
2128 w.write_all(&message_raw.0[..len]).await?;
2129
2130 Ok(len)
2131}
2132
2133#[cfg(feature = "mav2-message-signing")]
2139#[cfg(feature = "tokio")]
2140pub async fn write_v2_msg_async_signed<M: Message, W: AsyncWrite + Unpin>(
2141 w: &mut W,
2142 header: MavHeader,
2143 data: &M,
2144 signing_data: Option<&SigningData>,
2145) -> Result<usize, MessageWriteError> {
2146 let mut message_raw = MAVLinkV2MessageRaw::new();
2147
2148 let signature_len = if let Some(signing_data) = signing_data {
2149 if signing_data.config.sign_outgoing {
2150 message_raw.serialize_message_for_signing(header, data);
2151 signing_data.sign_message(&mut message_raw);
2152 MAVLinkV2MessageRaw::SIGNATURE_SIZE
2153 } else {
2154 message_raw.serialize_message(header, data);
2155 0
2156 }
2157 } else {
2158 message_raw.serialize_message(header, data);
2159 0
2160 };
2161
2162 let payload_length: usize = message_raw.payload_length().into();
2163 let len = 1 + MAVLinkV2MessageRaw::HEADER_SIZE + payload_length + 2 + signature_len;
2164
2165 w.write_all(&message_raw.0[..len]).await?;
2166
2167 Ok(len)
2168}
2169
2170#[cfg(all(feature = "embedded", not(feature = "std")))]
2179pub async fn write_v2_msg_async<M: Message>(
2180 w: &mut impl embedded_io_async::Write,
2181 header: MavHeader,
2182 data: &M,
2183) -> Result<usize, MessageWriteError> {
2184 let mut message_raw = MAVLinkV2MessageRaw::new();
2185 message_raw.serialize_message(header, data);
2186
2187 let payload_length: usize = message_raw.payload_length().into();
2188 let len = 1 + MAVLinkV2MessageRaw::HEADER_SIZE + payload_length + 2;
2189
2190 w.write_all(&message_raw.0[..len])
2191 .await
2192 .map_err(|_| MessageWriteError::Io)?;
2193
2194 Ok(len)
2195}
2196
2197pub fn write_v1_msg<M: Message, W: Write>(
2203 w: &mut W,
2204 header: MavHeader,
2205 data: &M,
2206) -> Result<usize, MessageWriteError> {
2207 if data.message_id() > u8::MAX.into() {
2208 return Err(MessageWriteError::MAVLink2Only);
2209 }
2210 let mut message_raw = MAVLinkV1MessageRaw::new();
2211 message_raw.serialize_message(header, data);
2212
2213 let payload_length: usize = message_raw.payload_length().into();
2214 let len = 1 + MAVLinkV1MessageRaw::HEADER_SIZE + payload_length + 2;
2215
2216 w.write_all(&message_raw.0[..len])?;
2217
2218 Ok(len)
2219}
2220
2221#[cfg(feature = "tokio")]
2227pub async fn write_v1_msg_async<M: Message, W: AsyncWrite + Unpin>(
2228 w: &mut W,
2229 header: MavHeader,
2230 data: &M,
2231) -> Result<usize, MessageWriteError> {
2232 if data.message_id() > u8::MAX.into() {
2233 return Err(MessageWriteError::MAVLink2Only);
2234 }
2235 let mut message_raw = MAVLinkV1MessageRaw::new();
2236 message_raw.serialize_message(header, data);
2237
2238 let payload_length: usize = message_raw.payload_length().into();
2239 let len = 1 + MAVLinkV1MessageRaw::HEADER_SIZE + payload_length + 2;
2240
2241 w.write_all(&message_raw.0[..len]).await?;
2242
2243 Ok(len)
2244}
2245
2246#[cfg(all(feature = "embedded", not(feature = "std")))]
2251pub async fn write_v1_msg_async<M: Message>(
2252 w: &mut impl embedded_io_async::Write,
2253 header: MavHeader,
2254 data: &M,
2255) -> Result<usize, MessageWriteError> {
2256 if data.message_id() > u8::MAX.into() {
2257 return Err(MessageWriteError::MAVLink2Only);
2258 }
2259 let mut message_raw = MAVLinkV1MessageRaw::new();
2260 message_raw.serialize_message(header, data);
2261
2262 let payload_length: usize = message_raw.payload_length().into();
2263 let len = 1 + MAVLinkV1MessageRaw::HEADER_SIZE + payload_length + 2;
2264
2265 w.write_all(&message_raw.0[..len])
2266 .await
2267 .map_err(|_| MessageWriteError::Io)?;
2268
2269 Ok(len)
2270}
2271
2272#[deprecated = "use read_versioned_raw_message instead"]
2273pub fn read_raw_versioned_msg<M: Message, R: Read>(
2274 r: &mut PeekReader<R>,
2275 version: ReadVersion,
2276) -> Result<MAVLinkMessageRaw, MessageReadError> {
2277 read_versioned_raw_message::<M, _>(r, version)
2278}
2279
2280#[cfg(feature = "tokio")]
2281#[deprecated = "use read_versioned_raw_message_async instead"]
2282pub async fn read_raw_versioned_msg_async<M: Message, R: tokio::io::AsyncRead + Unpin>(
2283 r: &mut AsyncPeekReader<R>,
2284 version: ReadVersion,
2285) -> Result<MAVLinkMessageRaw, MessageReadError> {
2286 read_versioned_raw_message_async::<M, _>(r, version).await
2287}
2288
2289#[cfg(feature = "mav2-message-signing")]
2290#[deprecated = "use read_versioned_raw_message_signed instead"]
2291pub fn read_raw_versioned_msg_signed<M: Message, R: Read>(
2292 r: &mut PeekReader<R>,
2293 version: ReadVersion,
2294 signing_data: Option<&SigningData>,
2295) -> Result<MAVLinkMessageRaw, MessageReadError> {
2296 read_versioned_raw_message_signed::<M, _>(r, version, signing_data)
2297}
2298
2299#[cfg(all(feature = "tokio", feature = "mav2-message-signing"))]
2300#[deprecated = "use read_versioned_raw_message_async_signed instead"]
2301pub async fn read_raw_versioned_msg_async_signed<M: Message, R: tokio::io::AsyncRead + Unpin>(
2302 r: &mut AsyncPeekReader<R>,
2303 version: ReadVersion,
2304 signing_data: Option<&SigningData>,
2305) -> Result<MAVLinkMessageRaw, MessageReadError> {
2306 read_versioned_raw_message_async_signed::<M, _>(r, version, signing_data).await
2307}