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>;
236}
237
238#[derive(Debug, Copy, Clone, PartialEq, Eq)]
240#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
241#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
242pub struct MavHeader {
243 pub system_id: u8,
245 pub component_id: u8,
247 pub sequence: u8,
249}
250
251#[derive(Debug, Copy, Clone, PartialEq, Eq)]
253#[cfg_attr(feature = "serde", derive(Serialize))]
254#[cfg_attr(feature = "serde", serde(tag = "type"))]
255#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
256pub enum MavlinkVersion {
257 V1,
259 V2,
261}
262
263pub const MAV_STX: u8 = 0xFE;
265
266pub const MAV_STX_V2: u8 = 0xFD;
268
269impl Default for MavHeader {
272 fn default() -> Self {
273 Self {
274 system_id: 255,
275 component_id: 0,
276 sequence: 0,
277 }
278 }
279}
280
281#[derive(Debug, Clone)]
285#[cfg_attr(feature = "serde", derive(Serialize))]
286#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
287pub struct MavFrame<M: Message> {
288 pub header: MavHeader,
290 pub msg: M,
292 pub protocol_version: MavlinkVersion,
294}
295
296impl<M: Message> MavFrame<M> {
297 pub fn ser(&self, buf: &mut [u8]) -> usize {
306 let mut buf = bytes_mut::BytesMut::new(buf);
307
308 let mut payload_buf = [0u8; 255];
310 let payload_len = self.msg.ser(self.protocol_version, &mut payload_buf);
311
312 buf.put_u8(self.header.sequence);
331 buf.put_u8(self.header.system_id);
332 buf.put_u8(self.header.component_id);
333
334 match self.protocol_version {
336 MavlinkVersion::V2 => {
337 let bytes: [u8; 4] = self.msg.message_id().to_le_bytes();
338 buf.put_slice(&bytes[..3]);
339 }
340 MavlinkVersion::V1 => {
341 buf.put_u8(
342 self.msg
343 .message_id()
344 .try_into()
345 .expect("message is MAVLink 2 only"),
346 );
347 }
348 }
349
350 buf.put_slice(&payload_buf[..payload_len]);
351 buf.len()
352 }
353
354 pub fn deser(version: MavlinkVersion, input: &[u8]) -> Result<Self, ParserError> {
363 let mut buf = Bytes::new(input);
364
365 let sequence = buf.get_u8()?;
375 let system_id = buf.get_u8()?;
376 let component_id = buf.get_u8()?;
377 let header = MavHeader {
378 system_id,
379 component_id,
380 sequence,
381 };
382
383 let msg_id = match version {
384 MavlinkVersion::V2 => buf.get_u24_le()?,
385 MavlinkVersion::V1 => buf.get_u8()?.into(),
386 };
387
388 M::parse(version, msg_id, buf.remaining_bytes()).map(|msg| Self {
389 header,
390 msg,
391 protocol_version: version,
392 })
393 }
394
395 pub fn header(&self) -> MavHeader {
397 self.header
398 }
399}
400
401pub fn calculate_crc(data: &[u8], extra_crc: u8) -> u16 {
403 let mut crc_calculator = CRCu16::crc16mcrf4cc();
404 crc_calculator.digest(data);
405
406 crc_calculator.digest(&[extra_crc]);
407 crc_calculator.get_crc()
408}
409
410#[derive(Debug, Clone, Copy, PartialEq, Eq)]
411pub enum ReadVersion {
413 Single(MavlinkVersion),
415 Any,
417}
418
419impl ReadVersion {
420 #[cfg(feature = "std")]
421 fn from_conn_cfg<C: MavConnection<M>, M: Message>(conn: &C) -> Self {
422 if conn.allow_recv_any_version() {
423 Self::Any
424 } else {
425 conn.protocol_version().into()
426 }
427 }
428 #[cfg(feature = "tokio")]
429 fn from_async_conn_cfg<C: AsyncMavConnection<M>, M: Message + Sync + Send>(conn: &C) -> Self {
430 if conn.allow_recv_any_version() {
431 Self::Any
432 } else {
433 conn.protocol_version().into()
434 }
435 }
436}
437
438impl From<MavlinkVersion> for ReadVersion {
439 fn from(value: MavlinkVersion) -> Self {
440 Self::Single(value)
441 }
442}
443
444pub fn read_versioned_msg<M: Message, R: Read>(
450 r: &mut PeekReader<R>,
451 version: ReadVersion,
452) -> Result<(MavHeader, M), MessageReadError> {
453 match version {
454 ReadVersion::Single(MavlinkVersion::V2) => read_v2_msg(r),
455 ReadVersion::Single(MavlinkVersion::V1) => read_v1_msg(r),
456 ReadVersion::Any => read_any_msg(r),
457 }
458}
459
460pub fn read_versioned_raw_message<M: Message, R: Read>(
466 r: &mut PeekReader<R>,
467 version: ReadVersion,
468) -> Result<MAVLinkMessageRaw, MessageReadError> {
469 match version {
470 ReadVersion::Single(MavlinkVersion::V2) => {
471 Ok(MAVLinkMessageRaw::V2(read_v2_raw_message::<M, _>(r)?))
472 }
473 ReadVersion::Single(MavlinkVersion::V1) => {
474 Ok(MAVLinkMessageRaw::V1(read_v1_raw_message::<M, _>(r)?))
475 }
476 ReadVersion::Any => read_any_raw_message::<M, _>(r),
477 }
478}
479
480#[cfg(feature = "tokio")]
486pub async fn read_versioned_msg_async<M: Message, R: tokio::io::AsyncRead + Unpin>(
487 r: &mut AsyncPeekReader<R>,
488 version: ReadVersion,
489) -> Result<(MavHeader, M), MessageReadError> {
490 match version {
491 ReadVersion::Single(MavlinkVersion::V2) => read_v2_msg_async(r).await,
492 ReadVersion::Single(MavlinkVersion::V1) => read_v1_msg_async(r).await,
493 ReadVersion::Any => read_any_msg_async(r).await,
494 }
495}
496
497#[cfg(feature = "tokio")]
503pub async fn read_versioned_raw_message_async<M: Message, R: tokio::io::AsyncRead + Unpin>(
504 r: &mut AsyncPeekReader<R>,
505 version: ReadVersion,
506) -> Result<MAVLinkMessageRaw, MessageReadError> {
507 match version {
508 ReadVersion::Single(MavlinkVersion::V2) => Ok(MAVLinkMessageRaw::V2(
509 read_v2_raw_message_async::<M, _>(r).await?,
510 )),
511 ReadVersion::Single(MavlinkVersion::V1) => Ok(MAVLinkMessageRaw::V1(
512 read_v1_raw_message_async::<M, _>(r).await?,
513 )),
514 ReadVersion::Any => read_any_raw_message_async::<M, _>(r).await,
515 }
516}
517
518#[cfg(feature = "mav2-message-signing")]
527pub fn read_versioned_raw_message_signed<M: Message, R: Read>(
528 r: &mut PeekReader<R>,
529 version: ReadVersion,
530 signing_data: Option<&SigningData>,
531) -> Result<MAVLinkMessageRaw, MessageReadError> {
532 match version {
533 ReadVersion::Single(MavlinkVersion::V2) => Ok(MAVLinkMessageRaw::V2(
534 read_v2_raw_message_inner::<M, _>(r, signing_data)?,
535 )),
536 ReadVersion::Single(MavlinkVersion::V1) => {
537 Ok(MAVLinkMessageRaw::V1(read_v1_raw_message::<M, _>(r)?))
538 }
539 ReadVersion::Any => read_any_raw_message_inner::<M, _>(r, signing_data),
540 }
541}
542
543#[cfg(feature = "mav2-message-signing")]
552pub fn read_versioned_msg_signed<M: Message, R: Read>(
553 r: &mut PeekReader<R>,
554 version: ReadVersion,
555 signing_data: Option<&SigningData>,
556) -> Result<(MavHeader, M), MessageReadError> {
557 match version {
558 ReadVersion::Single(MavlinkVersion::V2) => read_v2_msg_inner(r, signing_data),
559 ReadVersion::Single(MavlinkVersion::V1) => read_v1_msg(r),
560 ReadVersion::Any => read_any_msg_inner(r, signing_data),
561 }
562}
563
564#[cfg(all(feature = "tokio", feature = "mav2-message-signing"))]
573pub async fn read_versioned_raw_message_async_signed<
574 M: Message,
575 R: tokio::io::AsyncRead + Unpin,
576>(
577 r: &mut AsyncPeekReader<R>,
578 version: ReadVersion,
579 signing_data: Option<&SigningData>,
580) -> Result<MAVLinkMessageRaw, MessageReadError> {
581 match version {
582 ReadVersion::Single(MavlinkVersion::V2) => Ok(MAVLinkMessageRaw::V2(
583 read_v2_raw_message_async_inner::<M, _>(r, signing_data).await?,
584 )),
585 ReadVersion::Single(MavlinkVersion::V1) => Ok(MAVLinkMessageRaw::V1(
586 read_v1_raw_message_async::<M, _>(r).await?,
587 )),
588 ReadVersion::Any => read_any_raw_message_async_inner::<M, _>(r, signing_data).await,
589 }
590}
591
592#[cfg(all(feature = "tokio", feature = "mav2-message-signing"))]
601pub async fn read_versioned_msg_async_signed<M: Message, R: tokio::io::AsyncRead + Unpin>(
602 r: &mut AsyncPeekReader<R>,
603 version: ReadVersion,
604 signing_data: Option<&SigningData>,
605) -> Result<(MavHeader, M), MessageReadError> {
606 match version {
607 ReadVersion::Single(MavlinkVersion::V2) => read_v2_msg_async_inner(r, signing_data).await,
608 ReadVersion::Single(MavlinkVersion::V1) => read_v1_msg_async(r).await,
609 ReadVersion::Any => read_any_msg_async_inner(r, signing_data).await,
610 }
611}
612
613#[derive(Debug, Copy, Clone, PartialEq, Eq)]
614pub struct MAVLinkV1MessageRaw([u8; 1 + Self::HEADER_SIZE + 255 + 2]);
619
620impl Default for MAVLinkV1MessageRaw {
621 fn default() -> Self {
622 Self::new()
623 }
624}
625
626impl MAVLinkV1MessageRaw {
627 const HEADER_SIZE: usize = 5;
628
629 pub const fn new() -> Self {
631 Self([0; 1 + Self::HEADER_SIZE + 255 + 2])
632 }
633
634 pub const fn from_bytes_unparsed(bytes: [u8; 1 + Self::HEADER_SIZE + 255 + 2]) -> Self {
638 Self(bytes)
639 }
640
641 #[inline]
643 pub fn as_slice(&self) -> &[u8] {
644 &self.0
645 }
646
647 #[inline]
649 pub fn as_mut_slice(&mut self) -> &mut [u8] {
650 &mut self.0
651 }
652
653 #[inline]
655 pub fn into_inner(self) -> [u8; 1 + Self::HEADER_SIZE + 255 + 2] {
656 self.0
657 }
658
659 #[inline]
661 pub fn header(&self) -> &[u8] {
662 &self.0[1..=Self::HEADER_SIZE]
663 }
664
665 #[inline]
667 fn mut_header(&mut self) -> &mut [u8] {
668 &mut self.0[1..=Self::HEADER_SIZE]
669 }
670
671 #[inline]
673 pub fn payload_length(&self) -> u8 {
674 self.0[1]
675 }
676
677 #[inline]
679 pub fn sequence(&self) -> u8 {
680 self.0[2]
681 }
682
683 #[inline]
685 pub fn system_id(&self) -> u8 {
686 self.0[3]
687 }
688
689 #[inline]
691 pub fn component_id(&self) -> u8 {
692 self.0[4]
693 }
694
695 #[inline]
697 pub fn message_id(&self) -> u8 {
698 self.0[5]
699 }
700
701 #[inline]
703 pub fn payload(&self) -> &[u8] {
704 let payload_length: usize = self.payload_length().into();
705 &self.0[(1 + Self::HEADER_SIZE)..(1 + Self::HEADER_SIZE + payload_length)]
706 }
707
708 #[inline]
710 pub fn checksum(&self) -> u16 {
711 let payload_length: usize = self.payload_length().into();
712 u16::from_le_bytes([
713 self.0[1 + Self::HEADER_SIZE + payload_length],
714 self.0[1 + Self::HEADER_SIZE + payload_length + 1],
715 ])
716 }
717
718 #[inline]
719 fn mut_payload_and_checksum(&mut self) -> &mut [u8] {
720 let payload_length: usize = self.payload_length().into();
721 &mut self.0[(1 + Self::HEADER_SIZE)..(1 + Self::HEADER_SIZE + payload_length + 2)]
722 }
723
724 #[inline]
726 pub fn has_valid_crc<M: Message>(&self) -> bool {
727 let payload_length: usize = self.payload_length().into();
728 self.checksum()
729 == calculate_crc(
730 &self.0[1..(1 + Self::HEADER_SIZE + payload_length)],
731 M::extra_crc(self.message_id().into()),
732 )
733 }
734
735 pub fn raw_bytes(&self) -> &[u8] {
737 let payload_length = self.payload_length() as usize;
738 &self.0[..(1 + Self::HEADER_SIZE + payload_length + 2)]
739 }
740
741 fn serialize_stx_and_header_and_crc(
745 &mut self,
746 header: MavHeader,
747 msgid: u32,
748 payload_length: usize,
749 extra_crc: u8,
750 ) {
751 self.0[0] = MAV_STX;
752
753 let header_buf = self.mut_header();
754 header_buf.copy_from_slice(&[
755 payload_length as u8,
756 header.sequence,
757 header.system_id,
758 header.component_id,
759 msgid.try_into().unwrap(),
760 ]);
761
762 let crc = calculate_crc(
763 &self.0[1..(1 + Self::HEADER_SIZE + payload_length)],
764 extra_crc,
765 );
766 self.0[(1 + Self::HEADER_SIZE + payload_length)
767 ..(1 + Self::HEADER_SIZE + payload_length + 2)]
768 .copy_from_slice(&crc.to_le_bytes());
769 }
770
771 pub fn serialize_message<M: Message>(&mut self, header: MavHeader, message: &M) {
777 let payload_buf = &mut self.0[(1 + Self::HEADER_SIZE)..(1 + Self::HEADER_SIZE + 255)];
778 let payload_length = message.ser(MavlinkVersion::V1, payload_buf);
779
780 let message_id = message.message_id();
781 self.serialize_stx_and_header_and_crc(
782 header,
783 message_id,
784 payload_length,
785 M::extra_crc(message_id),
786 );
787 }
788
789 pub fn serialize_message_data<D: MessageData>(&mut self, header: MavHeader, message_data: &D) {
793 let payload_buf = &mut self.0[(1 + Self::HEADER_SIZE)..(1 + Self::HEADER_SIZE + 255)];
794 let payload_length = message_data.ser(MavlinkVersion::V1, payload_buf);
795
796 self.serialize_stx_and_header_and_crc(header, D::ID, payload_length, D::EXTRA_CRC);
797 }
798}
799
800fn try_decode_v1<M: Message, R: Read>(
801 reader: &mut PeekReader<R>,
802) -> Result<Option<MAVLinkV1MessageRaw>, MessageReadError> {
803 let mut message = MAVLinkV1MessageRaw::new();
804 let whole_header_size = MAVLinkV1MessageRaw::HEADER_SIZE + 1;
805
806 message.0[0] = MAV_STX;
807 let header = &reader.peek_exact(whole_header_size)?[1..whole_header_size];
808 message.mut_header().copy_from_slice(header);
809 let packet_length = message.raw_bytes().len();
810 let payload_and_checksum = &reader.peek_exact(packet_length)?[whole_header_size..packet_length];
811 message
812 .mut_payload_and_checksum()
813 .copy_from_slice(payload_and_checksum);
814
815 if message.has_valid_crc::<M>() {
818 reader.consume(message.raw_bytes().len());
819 Ok(Some(message))
820 } else {
821 Ok(None)
822 }
823}
824
825#[cfg(feature = "tokio")]
826async fn try_decode_v1_async<M: Message, R: tokio::io::AsyncRead + Unpin>(
828 reader: &mut AsyncPeekReader<R>,
829) -> Result<Option<MAVLinkV1MessageRaw>, MessageReadError> {
830 let mut message = MAVLinkV1MessageRaw::new();
831
832 message.0[0] = MAV_STX;
833 let header = &reader.peek_exact(MAVLinkV1MessageRaw::HEADER_SIZE).await?
834 [..MAVLinkV1MessageRaw::HEADER_SIZE];
835 message.mut_header().copy_from_slice(header);
836 let packet_length = message.raw_bytes().len() - 1;
837 let payload_and_checksum =
838 &reader.peek_exact(packet_length).await?[MAVLinkV1MessageRaw::HEADER_SIZE..packet_length];
839 message
840 .mut_payload_and_checksum()
841 .copy_from_slice(payload_and_checksum);
842
843 if message.has_valid_crc::<M>() {
846 reader.consume(message.raw_bytes().len() - 1);
847 Ok(Some(message))
848 } else {
849 Ok(None)
850 }
851}
852
853pub fn read_v1_raw_message<M: Message, R: Read>(
859 reader: &mut PeekReader<R>,
860) -> Result<MAVLinkV1MessageRaw, MessageReadError> {
861 loop {
862 while reader.peek_exact(1)?[0] != MAV_STX {
864 reader.consume(1);
865 }
866
867 if let Some(msg) = try_decode_v1::<M, _>(reader)? {
868 return Ok(msg);
869 }
870
871 reader.consume(1);
872 }
873}
874
875#[cfg(feature = "tokio")]
881pub async fn read_v1_raw_message_async<M: Message, R: tokio::io::AsyncRead + Unpin>(
882 reader: &mut AsyncPeekReader<R>,
883) -> Result<MAVLinkV1MessageRaw, MessageReadError> {
884 loop {
885 loop {
886 if reader.read_u8().await? == MAV_STX {
888 break;
889 }
890 }
891
892 if let Some(message) = try_decode_v1_async::<M, _>(reader).await? {
893 return Ok(message);
894 }
895 }
896}
897
898#[cfg(all(feature = "embedded", not(feature = "std")))]
905pub async fn read_v1_raw_message_async<M: Message>(
906 reader: &mut impl embedded_io_async::Read,
907) -> Result<MAVLinkV1MessageRaw, MessageReadError> {
908 loop {
909 let mut byte = [0u8];
911 loop {
912 reader
913 .read_exact(&mut byte)
914 .await
915 .map_err(|_| MessageReadError::Io)?;
916 if byte[0] == MAV_STX {
917 break;
918 }
919 }
920
921 let mut message = MAVLinkV1MessageRaw::new();
922
923 message.0[0] = MAV_STX;
924 reader
925 .read_exact(message.mut_header())
926 .await
927 .map_err(|_| MessageReadError::Io)?;
928 reader
929 .read_exact(message.mut_payload_and_checksum())
930 .await
931 .map_err(|_| MessageReadError::Io)?;
932
933 if message.has_valid_crc::<M>() {
936 return Ok(message);
937 }
938 }
939}
940
941pub fn read_v1_msg<M: Message, R: Read>(
947 r: &mut PeekReader<R>,
948) -> Result<(MavHeader, M), MessageReadError> {
949 let message = read_v1_raw_message::<M, _>(r)?;
950
951 Ok((
952 MavHeader {
953 sequence: message.sequence(),
954 system_id: message.system_id(),
955 component_id: message.component_id(),
956 },
957 M::parse(
958 MavlinkVersion::V1,
959 u32::from(message.message_id()),
960 message.payload(),
961 )?,
962 ))
963}
964
965#[cfg(feature = "tokio")]
971pub async fn read_v1_msg_async<M: Message, R: tokio::io::AsyncRead + Unpin>(
972 r: &mut AsyncPeekReader<R>,
973) -> Result<(MavHeader, M), MessageReadError> {
974 let message = read_v1_raw_message_async::<M, _>(r).await?;
975
976 Ok((
977 MavHeader {
978 sequence: message.sequence(),
979 system_id: message.system_id(),
980 component_id: message.component_id(),
981 },
982 M::parse(
983 MavlinkVersion::V1,
984 u32::from(message.message_id()),
985 message.payload(),
986 )?,
987 ))
988}
989
990#[cfg(all(feature = "embedded", not(feature = "std")))]
995pub async fn read_v1_msg_async<M: Message>(
996 r: &mut impl embedded_io_async::Read,
997) -> Result<(MavHeader, M), MessageReadError> {
998 let message = read_v1_raw_message_async::<M>(r).await?;
999
1000 Ok((
1001 MavHeader {
1002 sequence: message.sequence(),
1003 system_id: message.system_id(),
1004 component_id: message.component_id(),
1005 },
1006 M::parse(
1007 MavlinkVersion::V1,
1008 u32::from(message.message_id()),
1009 message.payload(),
1010 )?,
1011 ))
1012}
1013
1014const MAVLINK_IFLAG_SIGNED: u8 = 0x01;
1015const MAVLINK_SUPPORTED_IFLAGS: u8 = MAVLINK_IFLAG_SIGNED;
1016
1017#[derive(Debug, Copy, Clone, PartialEq, Eq)]
1018pub struct MAVLinkV2MessageRaw([u8; 1 + Self::HEADER_SIZE + 255 + 2 + Self::SIGNATURE_SIZE]);
1023
1024impl Default for MAVLinkV2MessageRaw {
1025 fn default() -> Self {
1026 Self::new()
1027 }
1028}
1029
1030impl MAVLinkV2MessageRaw {
1031 const HEADER_SIZE: usize = 9;
1032 const SIGNATURE_SIZE: usize = 13;
1033
1034 pub const fn new() -> Self {
1036 Self([0; 1 + Self::HEADER_SIZE + 255 + 2 + Self::SIGNATURE_SIZE])
1037 }
1038
1039 pub const fn from_bytes_unparsed(
1043 bytes: [u8; 1 + Self::HEADER_SIZE + 255 + 2 + Self::SIGNATURE_SIZE],
1044 ) -> Self {
1045 Self(bytes)
1046 }
1047
1048 #[inline]
1050 pub fn as_slice(&self) -> &[u8] {
1051 &self.0
1052 }
1053
1054 #[inline]
1056 pub fn as_mut_slice(&mut self) -> &mut [u8] {
1057 &mut self.0
1058 }
1059
1060 #[inline]
1062 pub fn into_inner(self) -> [u8; 1 + Self::HEADER_SIZE + 255 + 2 + Self::SIGNATURE_SIZE] {
1063 self.0
1064 }
1065
1066 #[inline]
1068 pub fn header(&self) -> &[u8] {
1069 &self.0[1..=Self::HEADER_SIZE]
1070 }
1071
1072 #[inline]
1074 fn mut_header(&mut self) -> &mut [u8] {
1075 &mut self.0[1..=Self::HEADER_SIZE]
1076 }
1077
1078 #[inline]
1080 pub fn payload_length(&self) -> u8 {
1081 self.0[1]
1082 }
1083
1084 #[inline]
1088 pub fn incompatibility_flags(&self) -> u8 {
1089 self.0[2]
1090 }
1091
1092 #[inline]
1096 pub fn incompatibility_flags_mut(&mut self) -> &mut u8 {
1097 &mut self.0[2]
1098 }
1099
1100 #[inline]
1102 pub fn compatibility_flags(&self) -> u8 {
1103 self.0[3]
1104 }
1105
1106 #[inline]
1108 pub fn sequence(&self) -> u8 {
1109 self.0[4]
1110 }
1111
1112 #[inline]
1114 pub fn system_id(&self) -> u8 {
1115 self.0[5]
1116 }
1117
1118 #[inline]
1120 pub fn component_id(&self) -> u8 {
1121 self.0[6]
1122 }
1123
1124 #[inline]
1126 pub fn message_id(&self) -> u32 {
1127 u32::from_le_bytes([self.0[7], self.0[8], self.0[9], 0])
1128 }
1129
1130 #[inline]
1132 pub fn payload(&self) -> &[u8] {
1133 let payload_length: usize = self.payload_length().into();
1134 &self.0[(1 + Self::HEADER_SIZE)..(1 + Self::HEADER_SIZE + payload_length)]
1135 }
1136
1137 #[inline]
1139 pub fn checksum(&self) -> u16 {
1140 let payload_length: usize = self.payload_length().into();
1141 u16::from_le_bytes([
1142 self.0[1 + Self::HEADER_SIZE + payload_length],
1143 self.0[1 + Self::HEADER_SIZE + payload_length + 1],
1144 ])
1145 }
1146
1147 #[cfg(feature = "mav2-message-signing")]
1149 #[inline]
1150 pub fn checksum_bytes(&self) -> &[u8] {
1151 let checksum_offset = 1 + Self::HEADER_SIZE + self.payload_length() as usize;
1152 &self.0[checksum_offset..(checksum_offset + 2)]
1153 }
1154
1155 #[cfg(feature = "mav2-message-signing")]
1159 #[inline]
1160 pub fn signature_link_id(&self) -> u8 {
1161 let payload_length: usize = self.payload_length().into();
1162 self.0[1 + Self::HEADER_SIZE + payload_length + 2]
1163 }
1164
1165 #[cfg(feature = "mav2-message-signing")]
1167 #[inline]
1168 pub fn signature_link_id_mut(&mut self) -> &mut u8 {
1169 let payload_length: usize = self.payload_length().into();
1170 &mut self.0[1 + Self::HEADER_SIZE + payload_length + 2]
1171 }
1172
1173 #[cfg(feature = "mav2-message-signing")]
1179 #[inline]
1180 pub fn signature_timestamp(&self) -> u64 {
1181 let mut timestamp_bytes = [0u8; 8];
1182 timestamp_bytes[0..6].copy_from_slice(self.signature_timestamp_bytes());
1183 u64::from_le_bytes(timestamp_bytes)
1184 }
1185
1186 #[cfg(feature = "mav2-message-signing")]
1190 #[inline]
1191 pub fn signature_timestamp_bytes(&self) -> &[u8] {
1192 let payload_length: usize = self.payload_length().into();
1193 let timestamp_start = 1 + Self::HEADER_SIZE + payload_length + 3;
1194 &self.0[timestamp_start..(timestamp_start + 6)]
1195 }
1196
1197 #[cfg(feature = "mav2-message-signing")]
1199 #[inline]
1200 pub fn signature_timestamp_bytes_mut(&mut self) -> &mut [u8] {
1201 let payload_length: usize = self.payload_length().into();
1202 let timestamp_start = 1 + Self::HEADER_SIZE + payload_length + 3;
1203 &mut self.0[timestamp_start..(timestamp_start + 6)]
1204 }
1205
1206 #[cfg(feature = "mav2-message-signing")]
1210 #[inline]
1211 pub fn signature_value(&self) -> &[u8] {
1212 let payload_length: usize = self.payload_length().into();
1213 let signature_start = 1 + Self::HEADER_SIZE + payload_length + 3 + 6;
1214 &self.0[signature_start..(signature_start + 6)]
1215 }
1216
1217 #[cfg(feature = "mav2-message-signing")]
1219 #[inline]
1220 pub fn signature_value_mut(&mut self) -> &mut [u8] {
1221 let payload_length: usize = self.payload_length().into();
1222 let signature_start = 1 + Self::HEADER_SIZE + payload_length + 3 + 6;
1223 &mut self.0[signature_start..(signature_start + 6)]
1224 }
1225
1226 fn mut_payload_and_checksum_and_sign(&mut self) -> &mut [u8] {
1227 let payload_length: usize = self.payload_length().into();
1228
1229 let signature_size = if (self.incompatibility_flags() & MAVLINK_IFLAG_SIGNED) == 0 {
1231 0
1232 } else {
1233 Self::SIGNATURE_SIZE
1234 };
1235
1236 &mut self.0
1237 [(1 + Self::HEADER_SIZE)..(1 + Self::HEADER_SIZE + payload_length + signature_size + 2)]
1238 }
1239
1240 #[inline]
1242 pub fn has_valid_crc<M: Message>(&self) -> bool {
1243 let payload_length: usize = self.payload_length().into();
1244 self.checksum()
1245 == calculate_crc(
1246 &self.0[1..(1 + Self::HEADER_SIZE + payload_length)],
1247 M::extra_crc(self.message_id()),
1248 )
1249 }
1250
1251 #[cfg(feature = "mav2-message-signing")]
1255 pub fn calculate_signature(&self, secret_key: &[u8], target_buffer: &mut [u8; 6]) {
1256 let mut hasher = Sha256::new();
1257 hasher.update(secret_key);
1258 hasher.update([MAV_STX_V2]);
1259 hasher.update(self.header());
1260 hasher.update(self.payload());
1261 hasher.update(self.checksum_bytes());
1262 hasher.update([self.signature_link_id()]);
1263 hasher.update(self.signature_timestamp_bytes());
1264 target_buffer.copy_from_slice(&hasher.finalize()[0..6]);
1265 }
1266
1267 pub fn raw_bytes(&self) -> &[u8] {
1269 let payload_length = self.payload_length() as usize;
1270
1271 let signature_size = if (self.incompatibility_flags() & MAVLINK_IFLAG_SIGNED) == 0 {
1272 0
1273 } else {
1274 Self::SIGNATURE_SIZE
1275 };
1276
1277 &self.0[..(1 + Self::HEADER_SIZE + payload_length + signature_size + 2)]
1278 }
1279
1280 fn serialize_stx_and_header_and_crc(
1281 &mut self,
1282 header: MavHeader,
1283 msgid: u32,
1284 payload_length: usize,
1285 extra_crc: u8,
1286 incompat_flags: u8,
1287 ) {
1288 self.0[0] = MAV_STX_V2;
1289 let msgid_bytes = msgid.to_le_bytes();
1290
1291 let header_buf = self.mut_header();
1292 header_buf.copy_from_slice(&[
1293 payload_length as u8,
1294 incompat_flags,
1295 0, header.sequence,
1297 header.system_id,
1298 header.component_id,
1299 msgid_bytes[0],
1300 msgid_bytes[1],
1301 msgid_bytes[2],
1302 ]);
1303
1304 let crc = calculate_crc(
1305 &self.0[1..(1 + Self::HEADER_SIZE + payload_length)],
1306 extra_crc,
1307 );
1308 self.0[(1 + Self::HEADER_SIZE + payload_length)
1309 ..(1 + Self::HEADER_SIZE + payload_length + 2)]
1310 .copy_from_slice(&crc.to_le_bytes());
1311 }
1312
1313 pub fn serialize_message<M: Message>(&mut self, header: MavHeader, message: &M) {
1317 let payload_buf = &mut self.0[(1 + Self::HEADER_SIZE)..(1 + Self::HEADER_SIZE + 255)];
1318 let payload_length = message.ser(MavlinkVersion::V2, payload_buf);
1319
1320 let message_id = message.message_id();
1321 self.serialize_stx_and_header_and_crc(
1322 header,
1323 message_id,
1324 payload_length,
1325 M::extra_crc(message_id),
1326 0,
1327 );
1328 }
1329
1330 pub fn serialize_message_for_signing<M: Message>(&mut self, header: MavHeader, message: &M) {
1335 let payload_buf = &mut self.0[(1 + Self::HEADER_SIZE)..(1 + Self::HEADER_SIZE + 255)];
1336 let payload_length = message.ser(MavlinkVersion::V2, payload_buf);
1337
1338 let message_id = message.message_id();
1339 self.serialize_stx_and_header_and_crc(
1340 header,
1341 message_id,
1342 payload_length,
1343 M::extra_crc(message_id),
1344 MAVLINK_IFLAG_SIGNED,
1345 );
1346 }
1347
1348 pub fn serialize_message_data<D: MessageData>(&mut self, header: MavHeader, message_data: &D) {
1349 let payload_buf = &mut self.0[(1 + Self::HEADER_SIZE)..(1 + Self::HEADER_SIZE + 255)];
1350 let payload_length = message_data.ser(MavlinkVersion::V2, payload_buf);
1351
1352 self.serialize_stx_and_header_and_crc(header, D::ID, payload_length, D::EXTRA_CRC, 0);
1353 }
1354}
1355
1356#[allow(unused_variables)]
1357fn try_decode_v2<M: Message, R: Read>(
1358 reader: &mut PeekReader<R>,
1359 signing_data: Option<&SigningData>,
1360) -> Result<Option<MAVLinkV2MessageRaw>, MessageReadError> {
1361 let mut message = MAVLinkV2MessageRaw::new();
1362 let whole_header_size = MAVLinkV2MessageRaw::HEADER_SIZE + 1;
1363
1364 message.0[0] = MAV_STX_V2;
1365 let header = &reader.peek_exact(whole_header_size)?[1..whole_header_size];
1366 message.mut_header().copy_from_slice(header);
1367
1368 if message.incompatibility_flags() & !MAVLINK_SUPPORTED_IFLAGS > 0 {
1369 reader.consume(1);
1371 return Ok(None);
1372 }
1373
1374 let packet_length = message.raw_bytes().len();
1375 let payload_and_checksum_and_sign =
1376 &reader.peek_exact(packet_length)?[whole_header_size..packet_length];
1377 message
1378 .mut_payload_and_checksum_and_sign()
1379 .copy_from_slice(payload_and_checksum_and_sign);
1380
1381 if message.has_valid_crc::<M>() {
1382 reader.consume(message.raw_bytes().len());
1384 } else {
1385 reader.consume(1);
1386 return Ok(None);
1387 }
1388
1389 #[cfg(feature = "mav2-message-signing")]
1390 if let Some(signing_data) = signing_data {
1391 if !signing_data.verify_signature(&message) {
1392 return Ok(None);
1393 }
1394 }
1395
1396 Ok(Some(message))
1397}
1398
1399#[cfg(feature = "tokio")]
1400#[allow(unused_variables)]
1401async fn try_decode_v2_async<M: Message, R: tokio::io::AsyncRead + Unpin>(
1403 reader: &mut AsyncPeekReader<R>,
1404 signing_data: Option<&SigningData>,
1405) -> Result<Option<MAVLinkV2MessageRaw>, MessageReadError> {
1406 let mut message = MAVLinkV2MessageRaw::new();
1407
1408 message.0[0] = MAV_STX_V2;
1409 let header = &reader.peek_exact(MAVLinkV2MessageRaw::HEADER_SIZE).await?
1410 [..MAVLinkV2MessageRaw::HEADER_SIZE];
1411 message.mut_header().copy_from_slice(header);
1412
1413 if message.incompatibility_flags() & !MAVLINK_SUPPORTED_IFLAGS > 0 {
1414 return Ok(None);
1416 }
1417
1418 let packet_length = message.raw_bytes().len() - 1;
1419 let payload_and_checksum_and_sign =
1420 &reader.peek_exact(packet_length).await?[MAVLinkV2MessageRaw::HEADER_SIZE..packet_length];
1421 message
1422 .mut_payload_and_checksum_and_sign()
1423 .copy_from_slice(payload_and_checksum_and_sign);
1424
1425 if message.has_valid_crc::<M>() {
1426 reader.consume(message.raw_bytes().len() - 1);
1428 } else {
1429 return Ok(None);
1430 }
1431
1432 #[cfg(feature = "mav2-message-signing")]
1433 if let Some(signing_data) = signing_data {
1434 if !signing_data.verify_signature(&message) {
1435 return Ok(None);
1436 }
1437 }
1438
1439 Ok(Some(message))
1440}
1441
1442#[inline]
1448pub fn read_v2_raw_message<M: Message, R: Read>(
1449 reader: &mut PeekReader<R>,
1450) -> Result<MAVLinkV2MessageRaw, MessageReadError> {
1451 read_v2_raw_message_inner::<M, R>(reader, None)
1452}
1453
1454#[cfg(feature = "mav2-message-signing")]
1460#[inline]
1461pub fn read_v2_raw_message_signed<M: Message, R: Read>(
1462 reader: &mut PeekReader<R>,
1463 signing_data: Option<&SigningData>,
1464) -> Result<MAVLinkV2MessageRaw, MessageReadError> {
1465 read_v2_raw_message_inner::<M, R>(reader, signing_data)
1466}
1467
1468#[allow(unused_variables)]
1469fn read_v2_raw_message_inner<M: Message, R: Read>(
1470 reader: &mut PeekReader<R>,
1471 signing_data: Option<&SigningData>,
1472) -> Result<MAVLinkV2MessageRaw, MessageReadError> {
1473 loop {
1474 while reader.peek_exact(1)?[0] != MAV_STX_V2 {
1476 reader.consume(1);
1477 }
1478
1479 if let Some(message) = try_decode_v2::<M, _>(reader, signing_data)? {
1480 return Ok(message);
1481 }
1482 }
1483}
1484
1485#[cfg(feature = "tokio")]
1491pub async fn read_v2_raw_message_async<M: Message, R: tokio::io::AsyncRead + Unpin>(
1492 reader: &mut AsyncPeekReader<R>,
1493) -> Result<MAVLinkV2MessageRaw, MessageReadError> {
1494 read_v2_raw_message_async_inner::<M, R>(reader, None).await
1495}
1496
1497#[cfg(feature = "tokio")]
1498#[allow(unused_variables)]
1499async fn read_v2_raw_message_async_inner<M: Message, R: tokio::io::AsyncRead + Unpin>(
1500 reader: &mut AsyncPeekReader<R>,
1501 signing_data: Option<&SigningData>,
1502) -> Result<MAVLinkV2MessageRaw, MessageReadError> {
1503 loop {
1504 loop {
1505 if reader.read_u8().await? == MAV_STX_V2 {
1507 break;
1508 }
1509 }
1510
1511 if let Some(message) = try_decode_v2_async::<M, _>(reader, signing_data).await? {
1512 return Ok(message);
1513 }
1514 }
1515}
1516
1517#[cfg(all(feature = "tokio", feature = "mav2-message-signing"))]
1523pub async fn read_v2_raw_message_async_signed<M: Message, R: tokio::io::AsyncRead + Unpin>(
1524 reader: &mut AsyncPeekReader<R>,
1525 signing_data: Option<&SigningData>,
1526) -> Result<MAVLinkV2MessageRaw, MessageReadError> {
1527 read_v2_raw_message_async_inner::<M, R>(reader, signing_data).await
1528}
1529
1530#[cfg(all(feature = "embedded", not(feature = "std")))]
1536pub async fn read_v2_raw_message_async<M: Message>(
1537 reader: &mut impl embedded_io_async::Read,
1538) -> Result<MAVLinkV2MessageRaw, MessageReadError> {
1539 loop {
1540 let mut byte = [0u8];
1542 loop {
1543 reader
1544 .read_exact(&mut byte)
1545 .await
1546 .map_err(|_| MessageReadError::Io)?;
1547 if byte[0] == MAV_STX_V2 {
1548 break;
1549 }
1550 }
1551
1552 let mut message = MAVLinkV2MessageRaw::new();
1553
1554 message.0[0] = MAV_STX_V2;
1555 reader
1556 .read_exact(message.mut_header())
1557 .await
1558 .map_err(|_| MessageReadError::Io)?;
1559
1560 if message.incompatibility_flags() & !MAVLINK_SUPPORTED_IFLAGS > 0 {
1561 continue;
1563 }
1564
1565 reader
1566 .read_exact(message.mut_payload_and_checksum_and_sign())
1567 .await
1568 .map_err(|_| MessageReadError::Io)?;
1569
1570 if message.has_valid_crc::<M>() {
1573 return Ok(message);
1574 }
1575 }
1576}
1577
1578#[inline]
1584pub fn read_v2_msg<M: Message, R: Read>(
1585 read: &mut PeekReader<R>,
1586) -> Result<(MavHeader, M), MessageReadError> {
1587 read_v2_msg_inner(read, None)
1588}
1589
1590#[cfg(feature = "mav2-message-signing")]
1596#[inline]
1597pub fn read_v2_msg_signed<M: Message, R: Read>(
1598 read: &mut PeekReader<R>,
1599 signing_data: Option<&SigningData>,
1600) -> Result<(MavHeader, M), MessageReadError> {
1601 read_v2_msg_inner(read, signing_data)
1602}
1603
1604fn read_v2_msg_inner<M: Message, R: Read>(
1605 read: &mut PeekReader<R>,
1606 signing_data: Option<&SigningData>,
1607) -> Result<(MavHeader, M), MessageReadError> {
1608 let message = read_v2_raw_message_inner::<M, _>(read, signing_data)?;
1609
1610 Ok((
1611 MavHeader {
1612 sequence: message.sequence(),
1613 system_id: message.system_id(),
1614 component_id: message.component_id(),
1615 },
1616 M::parse(MavlinkVersion::V2, message.message_id(), message.payload())?,
1617 ))
1618}
1619
1620#[cfg(feature = "tokio")]
1626pub async fn read_v2_msg_async<M: Message, R: tokio::io::AsyncRead + Unpin>(
1627 read: &mut AsyncPeekReader<R>,
1628) -> Result<(MavHeader, M), MessageReadError> {
1629 read_v2_msg_async_inner(read, None).await
1630}
1631
1632#[cfg(all(feature = "tokio", feature = "mav2-message-signing"))]
1638pub async fn read_v2_msg_async_signed<M: Message, R: tokio::io::AsyncRead + Unpin>(
1639 read: &mut AsyncPeekReader<R>,
1640 signing_data: Option<&SigningData>,
1641) -> Result<(MavHeader, M), MessageReadError> {
1642 read_v2_msg_async_inner(read, signing_data).await
1643}
1644
1645#[cfg(feature = "tokio")]
1646async fn read_v2_msg_async_inner<M: Message, R: tokio::io::AsyncRead + Unpin>(
1647 read: &mut AsyncPeekReader<R>,
1648 signing_data: Option<&SigningData>,
1649) -> Result<(MavHeader, M), MessageReadError> {
1650 let message = read_v2_raw_message_async_inner::<M, _>(read, signing_data).await?;
1651
1652 Ok((
1653 MavHeader {
1654 sequence: message.sequence(),
1655 system_id: message.system_id(),
1656 component_id: message.component_id(),
1657 },
1658 M::parse(MavlinkVersion::V2, message.message_id(), message.payload())?,
1659 ))
1660}
1661
1662#[cfg(all(feature = "embedded", not(feature = "std")))]
1667pub async fn read_v2_msg_async<M: Message, R: embedded_io_async::Read>(
1668 r: &mut R,
1669) -> Result<(MavHeader, M), MessageReadError> {
1670 let message = read_v2_raw_message_async::<M>(r).await?;
1671
1672 Ok((
1673 MavHeader {
1674 sequence: message.sequence(),
1675 system_id: message.system_id(),
1676 component_id: message.component_id(),
1677 },
1678 M::parse(
1679 MavlinkVersion::V2,
1680 u32::from(message.message_id()),
1681 message.payload(),
1682 )?,
1683 ))
1684}
1685
1686pub enum MAVLinkMessageRaw {
1688 V1(MAVLinkV1MessageRaw),
1689 V2(MAVLinkV2MessageRaw),
1690}
1691
1692impl MAVLinkMessageRaw {
1693 pub fn payload(&self) -> &[u8] {
1694 match self {
1695 Self::V1(msg) => msg.payload(),
1696 Self::V2(msg) => msg.payload(),
1697 }
1698 }
1699 pub fn sequence(&self) -> u8 {
1700 match self {
1701 Self::V1(msg) => msg.sequence(),
1702 Self::V2(msg) => msg.sequence(),
1703 }
1704 }
1705 pub fn system_id(&self) -> u8 {
1706 match self {
1707 Self::V1(msg) => msg.system_id(),
1708 Self::V2(msg) => msg.system_id(),
1709 }
1710 }
1711 pub fn component_id(&self) -> u8 {
1712 match self {
1713 Self::V1(msg) => msg.component_id(),
1714 Self::V2(msg) => msg.component_id(),
1715 }
1716 }
1717 pub fn message_id(&self) -> u32 {
1718 match self {
1719 Self::V1(msg) => u32::from(msg.message_id()),
1720 Self::V2(msg) => msg.message_id(),
1721 }
1722 }
1723 pub fn version(&self) -> MavlinkVersion {
1724 match self {
1725 Self::V1(_) => MavlinkVersion::V1,
1726 Self::V2(_) => MavlinkVersion::V2,
1727 }
1728 }
1729}
1730
1731#[inline]
1737pub fn read_any_raw_message<M: Message, R: Read>(
1738 reader: &mut PeekReader<R>,
1739) -> Result<MAVLinkMessageRaw, MessageReadError> {
1740 read_any_raw_message_inner::<M, R>(reader, None)
1741}
1742
1743#[cfg(feature = "mav2-message-signing")]
1749#[inline]
1750pub fn read_any_raw_message_signed<M: Message, R: Read>(
1751 reader: &mut PeekReader<R>,
1752 signing_data: Option<&SigningData>,
1753) -> Result<MAVLinkMessageRaw, MessageReadError> {
1754 read_any_raw_message_inner::<M, R>(reader, signing_data)
1755}
1756
1757#[allow(unused_variables)]
1758fn read_any_raw_message_inner<M: Message, R: Read>(
1759 reader: &mut PeekReader<R>,
1760 signing_data: Option<&SigningData>,
1761) -> Result<MAVLinkMessageRaw, MessageReadError> {
1762 loop {
1763 let version = loop {
1765 let byte = reader.peek_exact(1)?[0];
1766 if byte == MAV_STX {
1767 break MavlinkVersion::V1;
1768 }
1769 if byte == MAV_STX_V2 {
1770 break MavlinkVersion::V2;
1771 }
1772 reader.consume(1);
1773 };
1774 match version {
1775 MavlinkVersion::V1 => {
1776 if let Some(message) = try_decode_v1::<M, _>(reader)? {
1777 #[cfg(feature = "mav2-message-signing")]
1779 if let Some(signing) = signing_data {
1780 if signing.config.allow_unsigned {
1781 return Ok(MAVLinkMessageRaw::V1(message));
1782 }
1783 } else {
1784 return Ok(MAVLinkMessageRaw::V1(message));
1785 }
1786 #[cfg(not(feature = "mav2-message-signing"))]
1787 return Ok(MAVLinkMessageRaw::V1(message));
1788 }
1789
1790 reader.consume(1);
1791 }
1792 MavlinkVersion::V2 => {
1793 if let Some(message) = try_decode_v2::<M, _>(reader, signing_data)? {
1794 return Ok(MAVLinkMessageRaw::V2(message));
1795 }
1796 }
1797 }
1798 }
1799}
1800
1801#[cfg(feature = "tokio")]
1807pub async fn read_any_raw_message_async<M: Message, R: tokio::io::AsyncRead + Unpin>(
1808 reader: &mut AsyncPeekReader<R>,
1809) -> Result<MAVLinkMessageRaw, MessageReadError> {
1810 read_any_raw_message_async_inner::<M, R>(reader, None).await
1811}
1812
1813#[cfg(all(feature = "tokio", feature = "mav2-message-signing"))]
1821pub async fn read_any_raw_message_async_signed<M: Message, R: tokio::io::AsyncRead + Unpin>(
1822 reader: &mut AsyncPeekReader<R>,
1823 signing_data: Option<&SigningData>,
1824) -> Result<MAVLinkMessageRaw, MessageReadError> {
1825 read_any_raw_message_async_inner::<M, R>(reader, signing_data).await
1826}
1827
1828#[cfg(feature = "tokio")]
1829#[allow(unused_variables)]
1830async fn read_any_raw_message_async_inner<M: Message, R: tokio::io::AsyncRead + Unpin>(
1831 reader: &mut AsyncPeekReader<R>,
1832 signing_data: Option<&SigningData>,
1833) -> Result<MAVLinkMessageRaw, MessageReadError> {
1834 loop {
1835 let version = loop {
1837 let read = reader.read_u8().await?;
1838 if read == MAV_STX {
1839 break MavlinkVersion::V1;
1840 }
1841 if read == MAV_STX_V2 {
1842 break MavlinkVersion::V2;
1843 }
1844 };
1845
1846 match version {
1847 MavlinkVersion::V1 => {
1848 if let Some(message) = try_decode_v1_async::<M, _>(reader).await? {
1849 #[cfg(feature = "mav2-message-signing")]
1851 if let Some(signing) = signing_data {
1852 if signing.config.allow_unsigned {
1853 return Ok(MAVLinkMessageRaw::V1(message));
1854 }
1855 } else {
1856 return Ok(MAVLinkMessageRaw::V1(message));
1857 }
1858 #[cfg(not(feature = "mav2-message-signing"))]
1859 return Ok(MAVLinkMessageRaw::V1(message));
1860 }
1861 }
1862 MavlinkVersion::V2 => {
1863 if let Some(message) = try_decode_v2_async::<M, _>(reader, signing_data).await? {
1864 return Ok(MAVLinkMessageRaw::V2(message));
1865 }
1866 }
1867 }
1868 }
1869}
1870
1871#[inline]
1877pub fn read_any_msg<M: Message, R: Read>(
1878 read: &mut PeekReader<R>,
1879) -> Result<(MavHeader, M), MessageReadError> {
1880 read_any_msg_inner(read, None)
1881}
1882
1883#[cfg(feature = "mav2-message-signing")]
1891#[inline]
1892pub fn read_any_msg_signed<M: Message, R: Read>(
1893 read: &mut PeekReader<R>,
1894 signing_data: Option<&SigningData>,
1895) -> Result<(MavHeader, M), MessageReadError> {
1896 read_any_msg_inner(read, signing_data)
1897}
1898
1899fn read_any_msg_inner<M: Message, R: Read>(
1900 read: &mut PeekReader<R>,
1901 signing_data: Option<&SigningData>,
1902) -> Result<(MavHeader, M), MessageReadError> {
1903 let message = read_any_raw_message_inner::<M, _>(read, signing_data)?;
1904 Ok((
1905 MavHeader {
1906 sequence: message.sequence(),
1907 system_id: message.system_id(),
1908 component_id: message.component_id(),
1909 },
1910 M::parse(message.version(), message.message_id(), message.payload())?,
1911 ))
1912}
1913
1914#[cfg(feature = "tokio")]
1920pub async fn read_any_msg_async<M: Message, R: tokio::io::AsyncRead + Unpin>(
1921 read: &mut AsyncPeekReader<R>,
1922) -> Result<(MavHeader, M), MessageReadError> {
1923 read_any_msg_async_inner(read, None).await
1924}
1925
1926#[cfg(all(feature = "tokio", feature = "mav2-message-signing"))]
1934#[inline]
1935pub async fn read_any_msg_async_signed<M: Message, R: tokio::io::AsyncRead + Unpin>(
1936 read: &mut AsyncPeekReader<R>,
1937 signing_data: Option<&SigningData>,
1938) -> Result<(MavHeader, M), MessageReadError> {
1939 read_any_msg_async_inner(read, signing_data).await
1940}
1941
1942#[cfg(feature = "tokio")]
1943async fn read_any_msg_async_inner<M: Message, R: tokio::io::AsyncRead + Unpin>(
1944 read: &mut AsyncPeekReader<R>,
1945 signing_data: Option<&SigningData>,
1946) -> Result<(MavHeader, M), MessageReadError> {
1947 let message = read_any_raw_message_async_inner::<M, _>(read, signing_data).await?;
1948
1949 Ok((
1950 MavHeader {
1951 sequence: message.sequence(),
1952 system_id: message.system_id(),
1953 component_id: message.component_id(),
1954 },
1955 M::parse(message.version(), message.message_id(), message.payload())?,
1956 ))
1957}
1958
1959pub fn write_versioned_msg<M: Message, W: Write>(
1965 w: &mut W,
1966 version: MavlinkVersion,
1967 header: MavHeader,
1968 data: &M,
1969) -> Result<usize, MessageWriteError> {
1970 match version {
1971 MavlinkVersion::V2 => write_v2_msg(w, header, data),
1972 MavlinkVersion::V1 => write_v1_msg(w, header, data),
1973 }
1974}
1975
1976#[cfg(feature = "mav2-message-signing")]
1984pub fn write_versioned_msg_signed<M: Message, W: Write>(
1985 w: &mut W,
1986 version: MavlinkVersion,
1987 header: MavHeader,
1988 data: &M,
1989 signing_data: Option<&SigningData>,
1990) -> Result<usize, MessageWriteError> {
1991 match version {
1992 MavlinkVersion::V2 => write_v2_msg_signed(w, header, data, signing_data),
1993 MavlinkVersion::V1 => write_v1_msg(w, header, data),
1994 }
1995}
1996
1997#[cfg(feature = "tokio")]
2003pub async fn write_versioned_msg_async<M: Message, W: AsyncWrite + Unpin>(
2004 w: &mut W,
2005 version: MavlinkVersion,
2006 header: MavHeader,
2007 data: &M,
2008) -> Result<usize, MessageWriteError> {
2009 match version {
2010 MavlinkVersion::V2 => write_v2_msg_async(w, header, data).await,
2011 MavlinkVersion::V1 => write_v1_msg_async(w, header, data).await,
2012 }
2013}
2014
2015#[cfg(all(feature = "tokio", feature = "mav2-message-signing"))]
2023pub async fn write_versioned_msg_async_signed<M: Message, W: AsyncWrite + Unpin>(
2024 w: &mut W,
2025 version: MavlinkVersion,
2026 header: MavHeader,
2027 data: &M,
2028 signing_data: Option<&SigningData>,
2029) -> Result<usize, MessageWriteError> {
2030 match version {
2031 MavlinkVersion::V2 => write_v2_msg_async_signed(w, header, data, signing_data).await,
2032 MavlinkVersion::V1 => write_v1_msg_async(w, header, data).await,
2033 }
2034}
2035
2036#[cfg(all(feature = "embedded", not(feature = "std")))]
2041pub async fn write_versioned_msg_async<M: Message>(
2042 w: &mut impl embedded_io_async::Write,
2043 version: MavlinkVersion,
2044 header: MavHeader,
2045 data: &M,
2046) -> Result<usize, MessageWriteError> {
2047 match version {
2048 MavlinkVersion::V2 => write_v2_msg_async(w, header, data).await,
2049 MavlinkVersion::V1 => write_v1_msg_async(w, header, data).await,
2050 }
2051}
2052
2053pub fn write_v2_msg<M: Message, W: Write>(
2059 w: &mut W,
2060 header: MavHeader,
2061 data: &M,
2062) -> Result<usize, MessageWriteError> {
2063 let mut message_raw = MAVLinkV2MessageRaw::new();
2064 message_raw.serialize_message(header, data);
2065
2066 let payload_length: usize = message_raw.payload_length().into();
2067 let len = 1 + MAVLinkV2MessageRaw::HEADER_SIZE + payload_length + 2;
2068
2069 w.write_all(&message_raw.0[..len])?;
2070
2071 Ok(len)
2072}
2073
2074#[cfg(feature = "mav2-message-signing")]
2080pub fn write_v2_msg_signed<M: Message, W: Write>(
2081 w: &mut W,
2082 header: MavHeader,
2083 data: &M,
2084 signing_data: Option<&SigningData>,
2085) -> Result<usize, MessageWriteError> {
2086 let mut message_raw = MAVLinkV2MessageRaw::new();
2087
2088 let signature_len = if let Some(signing_data) = signing_data {
2089 if signing_data.config.sign_outgoing {
2090 message_raw.serialize_message_for_signing(header, data);
2091 signing_data.sign_message(&mut message_raw);
2092 MAVLinkV2MessageRaw::SIGNATURE_SIZE
2093 } else {
2094 message_raw.serialize_message(header, data);
2095 0
2096 }
2097 } else {
2098 message_raw.serialize_message(header, data);
2099 0
2100 };
2101
2102 let payload_length: usize = message_raw.payload_length().into();
2103 let len = 1 + MAVLinkV2MessageRaw::HEADER_SIZE + payload_length + 2 + signature_len;
2104
2105 w.write_all(&message_raw.0[..len])?;
2106
2107 Ok(len)
2108}
2109
2110#[cfg(feature = "tokio")]
2116pub async fn write_v2_msg_async<M: Message, W: AsyncWrite + Unpin>(
2117 w: &mut W,
2118 header: MavHeader,
2119 data: &M,
2120) -> Result<usize, MessageWriteError> {
2121 let mut message_raw = MAVLinkV2MessageRaw::new();
2122 message_raw.serialize_message(header, data);
2123
2124 let payload_length: usize = message_raw.payload_length().into();
2125 let len = 1 + MAVLinkV2MessageRaw::HEADER_SIZE + payload_length + 2;
2126
2127 w.write_all(&message_raw.0[..len]).await?;
2128
2129 Ok(len)
2130}
2131
2132#[cfg(feature = "mav2-message-signing")]
2138#[cfg(feature = "tokio")]
2139pub async fn write_v2_msg_async_signed<M: Message, W: AsyncWrite + Unpin>(
2140 w: &mut W,
2141 header: MavHeader,
2142 data: &M,
2143 signing_data: Option<&SigningData>,
2144) -> Result<usize, MessageWriteError> {
2145 let mut message_raw = MAVLinkV2MessageRaw::new();
2146
2147 let signature_len = if let Some(signing_data) = signing_data {
2148 if signing_data.config.sign_outgoing {
2149 message_raw.serialize_message_for_signing(header, data);
2150 signing_data.sign_message(&mut message_raw);
2151 MAVLinkV2MessageRaw::SIGNATURE_SIZE
2152 } else {
2153 message_raw.serialize_message(header, data);
2154 0
2155 }
2156 } else {
2157 message_raw.serialize_message(header, data);
2158 0
2159 };
2160
2161 let payload_length: usize = message_raw.payload_length().into();
2162 let len = 1 + MAVLinkV2MessageRaw::HEADER_SIZE + payload_length + 2 + signature_len;
2163
2164 w.write_all(&message_raw.0[..len]).await?;
2165
2166 Ok(len)
2167}
2168
2169#[cfg(all(feature = "embedded", not(feature = "std")))]
2178pub async fn write_v2_msg_async<M: Message>(
2179 w: &mut impl embedded_io_async::Write,
2180 header: MavHeader,
2181 data: &M,
2182) -> Result<usize, MessageWriteError> {
2183 let mut message_raw = MAVLinkV2MessageRaw::new();
2184 message_raw.serialize_message(header, data);
2185
2186 let payload_length: usize = message_raw.payload_length().into();
2187 let len = 1 + MAVLinkV2MessageRaw::HEADER_SIZE + payload_length + 2;
2188
2189 w.write_all(&message_raw.0[..len])
2190 .await
2191 .map_err(|_| MessageWriteError::Io)?;
2192
2193 Ok(len)
2194}
2195
2196pub fn write_v1_msg<M: Message, W: Write>(
2202 w: &mut W,
2203 header: MavHeader,
2204 data: &M,
2205) -> Result<usize, MessageWriteError> {
2206 if data.message_id() > u8::MAX.into() {
2207 return Err(MessageWriteError::MAVLink2Only);
2208 }
2209 let mut message_raw = MAVLinkV1MessageRaw::new();
2210 message_raw.serialize_message(header, data);
2211
2212 let payload_length: usize = message_raw.payload_length().into();
2213 let len = 1 + MAVLinkV1MessageRaw::HEADER_SIZE + payload_length + 2;
2214
2215 w.write_all(&message_raw.0[..len])?;
2216
2217 Ok(len)
2218}
2219
2220#[cfg(feature = "tokio")]
2226pub async fn write_v1_msg_async<M: Message, W: AsyncWrite + Unpin>(
2227 w: &mut W,
2228 header: MavHeader,
2229 data: &M,
2230) -> Result<usize, MessageWriteError> {
2231 if data.message_id() > u8::MAX.into() {
2232 return Err(MessageWriteError::MAVLink2Only);
2233 }
2234 let mut message_raw = MAVLinkV1MessageRaw::new();
2235 message_raw.serialize_message(header, data);
2236
2237 let payload_length: usize = message_raw.payload_length().into();
2238 let len = 1 + MAVLinkV1MessageRaw::HEADER_SIZE + payload_length + 2;
2239
2240 w.write_all(&message_raw.0[..len]).await?;
2241
2242 Ok(len)
2243}
2244
2245#[cfg(all(feature = "embedded", not(feature = "std")))]
2250pub async fn write_v1_msg_async<M: Message>(
2251 w: &mut impl embedded_io_async::Write,
2252 header: MavHeader,
2253 data: &M,
2254) -> Result<usize, MessageWriteError> {
2255 if data.message_id() > u8::MAX.into() {
2256 return Err(MessageWriteError::MAVLink2Only);
2257 }
2258 let mut message_raw = MAVLinkV1MessageRaw::new();
2259 message_raw.serialize_message(header, data);
2260
2261 let payload_length: usize = message_raw.payload_length().into();
2262 let len = 1 + MAVLinkV1MessageRaw::HEADER_SIZE + payload_length + 2;
2263
2264 w.write_all(&message_raw.0[..len])
2265 .await
2266 .map_err(|_| MessageWriteError::Io)?;
2267
2268 Ok(len)
2269}
2270
2271#[deprecated = "use read_versioned_raw_message instead"]
2272pub fn read_raw_versioned_msg<M: Message, R: Read>(
2273 r: &mut PeekReader<R>,
2274 version: ReadVersion,
2275) -> Result<MAVLinkMessageRaw, MessageReadError> {
2276 read_versioned_raw_message::<M, _>(r, version)
2277}
2278
2279#[cfg(feature = "tokio")]
2280#[deprecated = "use read_versioned_raw_message_async instead"]
2281pub async fn read_raw_versioned_msg_async<M: Message, R: tokio::io::AsyncRead + Unpin>(
2282 r: &mut AsyncPeekReader<R>,
2283 version: ReadVersion,
2284) -> Result<MAVLinkMessageRaw, MessageReadError> {
2285 read_versioned_raw_message_async::<M, _>(r, version).await
2286}
2287
2288#[cfg(feature = "mav2-message-signing")]
2289#[deprecated = "use read_versioned_raw_message_signed instead"]
2290pub fn read_raw_versioned_msg_signed<M: Message, R: Read>(
2291 r: &mut PeekReader<R>,
2292 version: ReadVersion,
2293 signing_data: Option<&SigningData>,
2294) -> Result<MAVLinkMessageRaw, MessageReadError> {
2295 read_versioned_raw_message_signed::<M, _>(r, version, signing_data)
2296}
2297
2298#[cfg(all(feature = "tokio", feature = "mav2-message-signing"))]
2299#[deprecated = "use read_versioned_raw_message_async_signed instead"]
2300pub async fn read_raw_versioned_msg_async_signed<M: Message, R: tokio::io::AsyncRead + Unpin>(
2301 r: &mut AsyncPeekReader<R>,
2302 version: ReadVersion,
2303 signing_data: Option<&SigningData>,
2304) -> Result<MAVLinkMessageRaw, MessageReadError> {
2305 read_versioned_raw_message_async_signed::<M, _>(r, version, signing_data).await
2306}