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::{remove_trailing_zeroes, RustDefault};
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::{connect, Connectable, MavConnection};
119
120#[cfg(feature = "tokio-1")]
121mod async_connection;
122#[cfg(feature = "tokio-1")]
123pub use self::async_connection::{connect_async, AsyncConnectable, AsyncMavConnection};
124
125#[cfg(feature = "tokio-1")]
126pub mod async_peek_reader;
127#[cfg(feature = "tokio-1")]
128use async_peek_reader::AsyncPeekReader;
129#[cfg(feature = "tokio-1")]
130use tokio::io::{AsyncWrite, AsyncWriteExt};
131
132#[cfg(any(feature = "embedded", feature = "embedded-hal-02"))]
133pub mod embedded;
134#[cfg(any(feature = "embedded", feature = "embedded-hal-02"))]
135use embedded::{Read, Write};
136
137#[cfg(not(feature = "signing"))]
138type SigningData = ();
139#[cfg(feature = "signing")]
140mod signing;
141#[cfg(feature = "signing")]
142pub use self::signing::{SigningConfig, SigningData};
143#[cfg(feature = "signing")]
144use sha2::{Digest, Sha256};
145
146#[cfg(feature = "arbitrary")]
147use arbitrary::Arbitrary;
148
149#[cfg(any(feature = "std", feature = "tokio-1"))]
150mod connectable;
151
152#[cfg(any(feature = "std", feature = "tokio-1"))]
153pub use connectable::ConnectionAddress;
154
155#[cfg(feature = "direct-serial")]
156pub use connection::direct_serial::config::SerialConfig;
157
158#[cfg(feature = "tcp")]
159pub use connection::tcp::config::{TcpConfig, TcpMode};
160
161#[cfg(feature = "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 {
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(self.msg.message_id() as u8); }
343 }
344
345 buf.put_slice(&payload_buf[..payload_len]);
346 buf.len()
347 }
348
349 pub fn deser(version: MavlinkVersion, input: &[u8]) -> Result<Self, ParserError> {
361 let mut buf = Bytes::new(input);
362
363 let sequence = buf.get_u8();
373 let system_id = buf.get_u8();
374 let component_id = buf.get_u8();
375 let header = MavHeader {
376 system_id,
377 component_id,
378 sequence,
379 };
380
381 let msg_id = match version {
382 MavlinkVersion::V2 => buf.get_u24_le(),
383 MavlinkVersion::V1 => buf.get_u8().into(),
384 };
385
386 M::parse(version, msg_id, buf.remaining_bytes()).map(|msg| Self {
387 header,
388 msg,
389 protocol_version: version,
390 })
391 }
392
393 pub fn header(&self) -> MavHeader {
395 self.header
396 }
397}
398
399pub fn calculate_crc(data: &[u8], extra_crc: u8) -> u16 {
401 let mut crc_calculator = CRCu16::crc16mcrf4cc();
402 crc_calculator.digest(data);
403
404 crc_calculator.digest(&[extra_crc]);
405 crc_calculator.get_crc()
406}
407
408#[derive(Debug, Clone, Copy, PartialEq, Eq)]
409pub enum ReadVersion {
411 Single(MavlinkVersion),
413 Any,
415}
416
417impl ReadVersion {
418 #[cfg(feature = "std")]
419 fn from_conn_cfg<C: MavConnection<M>, M: Message>(conn: &C) -> Self {
420 if conn.allow_recv_any_version() {
421 Self::Any
422 } else {
423 conn.protocol_version().into()
424 }
425 }
426 #[cfg(feature = "tokio-1")]
427 fn from_async_conn_cfg<C: AsyncMavConnection<M>, M: Message + Sync + Send>(conn: &C) -> Self {
428 if conn.allow_recv_any_version() {
429 Self::Any
430 } else {
431 conn.protocol_version().into()
432 }
433 }
434}
435
436impl From<MavlinkVersion> for ReadVersion {
437 fn from(value: MavlinkVersion) -> Self {
438 Self::Single(value)
439 }
440}
441
442pub fn read_versioned_msg<M: Message, R: Read>(
448 r: &mut PeekReader<R>,
449 version: ReadVersion,
450) -> Result<(MavHeader, M), MessageReadError> {
451 match version {
452 ReadVersion::Single(MavlinkVersion::V2) => read_v2_msg(r),
453 ReadVersion::Single(MavlinkVersion::V1) => read_v1_msg(r),
454 ReadVersion::Any => read_any_msg(r),
455 }
456}
457
458pub fn read_versioned_raw_message<M: Message, R: Read>(
464 r: &mut PeekReader<R>,
465 version: ReadVersion,
466) -> Result<MAVLinkMessageRaw, MessageReadError> {
467 match version {
468 ReadVersion::Single(MavlinkVersion::V2) => {
469 Ok(MAVLinkMessageRaw::V2(read_v2_raw_message::<M, _>(r)?))
470 }
471 ReadVersion::Single(MavlinkVersion::V1) => {
472 Ok(MAVLinkMessageRaw::V1(read_v1_raw_message::<M, _>(r)?))
473 }
474 ReadVersion::Any => read_any_raw_message::<M, _>(r),
475 }
476}
477
478#[cfg(feature = "tokio-1")]
484pub async fn read_versioned_msg_async<M: Message, R: tokio::io::AsyncRead + Unpin>(
485 r: &mut AsyncPeekReader<R>,
486 version: ReadVersion,
487) -> Result<(MavHeader, M), MessageReadError> {
488 match version {
489 ReadVersion::Single(MavlinkVersion::V2) => read_v2_msg_async(r).await,
490 ReadVersion::Single(MavlinkVersion::V1) => read_v1_msg_async(r).await,
491 ReadVersion::Any => read_any_msg_async(r).await,
492 }
493}
494
495#[cfg(feature = "tokio-1")]
501pub async fn read_versioned_raw_message_async<M: Message, R: tokio::io::AsyncRead + Unpin>(
502 r: &mut AsyncPeekReader<R>,
503 version: ReadVersion,
504) -> Result<MAVLinkMessageRaw, MessageReadError> {
505 match version {
506 ReadVersion::Single(MavlinkVersion::V2) => Ok(MAVLinkMessageRaw::V2(
507 read_v2_raw_message_async::<M, _>(r).await?,
508 )),
509 ReadVersion::Single(MavlinkVersion::V1) => Ok(MAVLinkMessageRaw::V1(
510 read_v1_raw_message_async::<M, _>(r).await?,
511 )),
512 ReadVersion::Any => read_any_raw_message_async::<M, _>(r).await,
513 }
514}
515
516#[cfg(feature = "signing")]
525pub fn read_versioned_raw_message_signed<M: Message, R: Read>(
526 r: &mut PeekReader<R>,
527 version: ReadVersion,
528 signing_data: Option<&SigningData>,
529) -> Result<MAVLinkMessageRaw, MessageReadError> {
530 match version {
531 ReadVersion::Single(MavlinkVersion::V2) => Ok(MAVLinkMessageRaw::V2(
532 read_v2_raw_message_inner::<M, _>(r, signing_data)?,
533 )),
534 ReadVersion::Single(MavlinkVersion::V1) => {
535 Ok(MAVLinkMessageRaw::V1(read_v1_raw_message::<M, _>(r)?))
536 }
537 ReadVersion::Any => read_any_raw_message_inner::<M, _>(r, signing_data),
538 }
539}
540
541#[cfg(feature = "signing")]
550pub fn read_versioned_msg_signed<M: Message, R: Read>(
551 r: &mut PeekReader<R>,
552 version: ReadVersion,
553 signing_data: Option<&SigningData>,
554) -> Result<(MavHeader, M), MessageReadError> {
555 match version {
556 ReadVersion::Single(MavlinkVersion::V2) => read_v2_msg_inner(r, signing_data),
557 ReadVersion::Single(MavlinkVersion::V1) => read_v1_msg(r),
558 ReadVersion::Any => read_any_msg_inner(r, signing_data),
559 }
560}
561
562#[cfg(all(feature = "tokio-1", feature = "signing"))]
571pub async fn read_versioned_raw_message_async_signed<
572 M: Message,
573 R: tokio::io::AsyncRead + Unpin,
574>(
575 r: &mut AsyncPeekReader<R>,
576 version: ReadVersion,
577 signing_data: Option<&SigningData>,
578) -> Result<MAVLinkMessageRaw, MessageReadError> {
579 match version {
580 ReadVersion::Single(MavlinkVersion::V2) => Ok(MAVLinkMessageRaw::V2(
581 read_v2_raw_message_async_inner::<M, _>(r, signing_data).await?,
582 )),
583 ReadVersion::Single(MavlinkVersion::V1) => Ok(MAVLinkMessageRaw::V1(
584 read_v1_raw_message_async::<M, _>(r).await?,
585 )),
586 ReadVersion::Any => read_any_raw_message_async_inner::<M, _>(r, signing_data).await,
587 }
588}
589
590#[cfg(all(feature = "tokio-1", feature = "signing"))]
599pub async fn read_versioned_msg_async_signed<M: Message, R: tokio::io::AsyncRead + Unpin>(
600 r: &mut AsyncPeekReader<R>,
601 version: ReadVersion,
602 signing_data: Option<&SigningData>,
603) -> Result<(MavHeader, M), MessageReadError> {
604 match version {
605 ReadVersion::Single(MavlinkVersion::V2) => read_v2_msg_async_inner(r, signing_data).await,
606 ReadVersion::Single(MavlinkVersion::V1) => read_v1_msg_async(r).await,
607 ReadVersion::Any => read_any_msg_async_inner(r, signing_data).await,
608 }
609}
610
611#[derive(Debug, Copy, Clone, PartialEq, Eq)]
612pub struct MAVLinkV1MessageRaw([u8; 1 + Self::HEADER_SIZE + 255 + 2]);
617
618impl Default for MAVLinkV1MessageRaw {
619 fn default() -> Self {
620 Self::new()
621 }
622}
623
624impl MAVLinkV1MessageRaw {
625 const HEADER_SIZE: usize = 5;
626
627 pub const fn new() -> Self {
629 Self([0; 1 + Self::HEADER_SIZE + 255 + 2])
630 }
631
632 pub const fn from_bytes_unparsed(bytes: [u8; 1 + Self::HEADER_SIZE + 255 + 2]) -> Self {
636 Self(bytes)
637 }
638
639 #[inline]
641 pub fn as_slice(&self) -> &[u8] {
642 &self.0
643 }
644
645 #[inline]
647 pub fn as_mut_slice(&mut self) -> &mut [u8] {
648 &mut self.0
649 }
650
651 #[inline]
653 pub fn into_inner(self) -> [u8; 1 + Self::HEADER_SIZE + 255 + 2] {
654 self.0
655 }
656
657 #[inline]
659 pub fn header(&self) -> &[u8] {
660 &self.0[1..=Self::HEADER_SIZE]
661 }
662
663 #[inline]
665 fn mut_header(&mut self) -> &mut [u8] {
666 &mut self.0[1..=Self::HEADER_SIZE]
667 }
668
669 #[inline]
671 pub fn payload_length(&self) -> u8 {
672 self.0[1]
673 }
674
675 #[inline]
677 pub fn sequence(&self) -> u8 {
678 self.0[2]
679 }
680
681 #[inline]
683 pub fn system_id(&self) -> u8 {
684 self.0[3]
685 }
686
687 #[inline]
689 pub fn component_id(&self) -> u8 {
690 self.0[4]
691 }
692
693 #[inline]
695 pub fn message_id(&self) -> u8 {
696 self.0[5]
697 }
698
699 #[inline]
701 pub fn payload(&self) -> &[u8] {
702 let payload_length: usize = self.payload_length().into();
703 &self.0[(1 + Self::HEADER_SIZE)..(1 + Self::HEADER_SIZE + payload_length)]
704 }
705
706 #[inline]
708 pub fn checksum(&self) -> u16 {
709 let payload_length: usize = self.payload_length().into();
710 u16::from_le_bytes([
711 self.0[1 + Self::HEADER_SIZE + payload_length],
712 self.0[1 + Self::HEADER_SIZE + payload_length + 1],
713 ])
714 }
715
716 #[inline]
717 fn mut_payload_and_checksum(&mut self) -> &mut [u8] {
718 let payload_length: usize = self.payload_length().into();
719 &mut self.0[(1 + Self::HEADER_SIZE)..(1 + Self::HEADER_SIZE + payload_length + 2)]
720 }
721
722 #[inline]
724 pub fn has_valid_crc<M: Message>(&self) -> bool {
725 let payload_length: usize = self.payload_length().into();
726 self.checksum()
727 == calculate_crc(
728 &self.0[1..(1 + Self::HEADER_SIZE + payload_length)],
729 M::extra_crc(self.message_id().into()),
730 )
731 }
732
733 pub fn raw_bytes(&self) -> &[u8] {
735 let payload_length = self.payload_length() as usize;
736 &self.0[..(1 + Self::HEADER_SIZE + payload_length + 2)]
737 }
738
739 fn serialize_stx_and_header_and_crc(
743 &mut self,
744 header: MavHeader,
745 msgid: u32,
746 payload_length: usize,
747 extra_crc: u8,
748 ) {
749 self.0[0] = MAV_STX;
750
751 let header_buf = self.mut_header();
752 header_buf.copy_from_slice(&[
753 payload_length as u8,
754 header.sequence,
755 header.system_id,
756 header.component_id,
757 msgid.try_into().unwrap(),
758 ]);
759
760 let crc = calculate_crc(
761 &self.0[1..(1 + Self::HEADER_SIZE + payload_length)],
762 extra_crc,
763 );
764 self.0[(1 + Self::HEADER_SIZE + payload_length)
765 ..(1 + Self::HEADER_SIZE + payload_length + 2)]
766 .copy_from_slice(&crc.to_le_bytes());
767 }
768
769 pub fn serialize_message<M: Message>(&mut self, header: MavHeader, message: &M) {
775 let payload_buf = &mut self.0[(1 + Self::HEADER_SIZE)..(1 + Self::HEADER_SIZE + 255)];
776 let payload_length = message.ser(MavlinkVersion::V1, payload_buf);
777
778 let message_id = message.message_id();
779 self.serialize_stx_and_header_and_crc(
780 header,
781 message_id,
782 payload_length,
783 M::extra_crc(message_id),
784 );
785 }
786
787 pub fn serialize_message_data<D: MessageData>(&mut self, header: MavHeader, message_data: &D) {
791 let payload_buf = &mut self.0[(1 + Self::HEADER_SIZE)..(1 + Self::HEADER_SIZE + 255)];
792 let payload_length = message_data.ser(MavlinkVersion::V1, payload_buf);
793
794 self.serialize_stx_and_header_and_crc(header, D::ID, payload_length, D::EXTRA_CRC);
795 }
796}
797
798fn try_decode_v1<M: Message, R: Read>(
799 reader: &mut PeekReader<R>,
800) -> Result<Option<MAVLinkV1MessageRaw>, MessageReadError> {
801 let mut message = MAVLinkV1MessageRaw::new();
802 let whole_header_size = MAVLinkV1MessageRaw::HEADER_SIZE + 1;
803
804 message.0[0] = MAV_STX;
805 let header = &reader.peek_exact(whole_header_size)?[1..whole_header_size];
806 message.mut_header().copy_from_slice(header);
807 let packet_length = message.raw_bytes().len();
808 let payload_and_checksum = &reader.peek_exact(packet_length)?[whole_header_size..packet_length];
809 message
810 .mut_payload_and_checksum()
811 .copy_from_slice(payload_and_checksum);
812
813 if message.has_valid_crc::<M>() {
816 reader.consume(message.raw_bytes().len());
817 Ok(Some(message))
818 } else {
819 Ok(None)
820 }
821}
822
823#[cfg(feature = "tokio-1")]
824async fn try_decode_v1_async<M: Message, R: tokio::io::AsyncRead + Unpin>(
826 reader: &mut AsyncPeekReader<R>,
827) -> Result<Option<MAVLinkV1MessageRaw>, MessageReadError> {
828 let mut message = MAVLinkV1MessageRaw::new();
829
830 message.0[0] = MAV_STX;
831 let header = &reader.peek_exact(MAVLinkV1MessageRaw::HEADER_SIZE).await?
832 [..MAVLinkV1MessageRaw::HEADER_SIZE];
833 message.mut_header().copy_from_slice(header);
834 let packet_length = message.raw_bytes().len() - 1;
835 let payload_and_checksum =
836 &reader.peek_exact(packet_length).await?[MAVLinkV1MessageRaw::HEADER_SIZE..packet_length];
837 message
838 .mut_payload_and_checksum()
839 .copy_from_slice(payload_and_checksum);
840
841 if message.has_valid_crc::<M>() {
844 reader.consume(message.raw_bytes().len() - 1);
845 Ok(Some(message))
846 } else {
847 Ok(None)
848 }
849}
850
851pub fn read_v1_raw_message<M: Message, R: Read>(
857 reader: &mut PeekReader<R>,
858) -> Result<MAVLinkV1MessageRaw, MessageReadError> {
859 loop {
860 while reader.peek_exact(1)?[0] != MAV_STX {
862 reader.consume(1);
863 }
864
865 if let Some(msg) = try_decode_v1::<M, _>(reader)? {
866 return Ok(msg);
867 }
868
869 reader.consume(1);
870 }
871}
872
873#[cfg(feature = "tokio-1")]
879pub async fn read_v1_raw_message_async<M: Message, R: tokio::io::AsyncRead + Unpin>(
880 reader: &mut AsyncPeekReader<R>,
881) -> Result<MAVLinkV1MessageRaw, MessageReadError> {
882 loop {
883 loop {
884 if reader.read_u8().await? == MAV_STX {
886 break;
887 }
888 }
889
890 if let Some(message) = try_decode_v1_async::<M, _>(reader).await? {
891 return Ok(message);
892 }
893 }
894}
895
896#[cfg(feature = "embedded")]
903pub async fn read_v1_raw_message_async<M: Message>(
904 reader: &mut impl embedded_io_async::Read,
905) -> Result<MAVLinkV1MessageRaw, MessageReadError> {
906 loop {
907 let mut byte = [0u8];
909 loop {
910 reader
911 .read_exact(&mut byte)
912 .await
913 .map_err(|_| MessageReadError::Io)?;
914 if byte[0] == MAV_STX {
915 break;
916 }
917 }
918
919 let mut message = MAVLinkV1MessageRaw::new();
920
921 message.0[0] = MAV_STX;
922 reader
923 .read_exact(message.mut_header())
924 .await
925 .map_err(|_| MessageReadError::Io)?;
926 reader
927 .read_exact(message.mut_payload_and_checksum())
928 .await
929 .map_err(|_| MessageReadError::Io)?;
930
931 if message.has_valid_crc::<M>() {
934 return Ok(message);
935 }
936 }
937}
938
939pub fn read_v1_msg<M: Message, R: Read>(
945 r: &mut PeekReader<R>,
946) -> Result<(MavHeader, M), MessageReadError> {
947 let message = read_v1_raw_message::<M, _>(r)?;
948
949 Ok((
950 MavHeader {
951 sequence: message.sequence(),
952 system_id: message.system_id(),
953 component_id: message.component_id(),
954 },
955 M::parse(
956 MavlinkVersion::V1,
957 u32::from(message.message_id()),
958 message.payload(),
959 )?,
960 ))
961}
962
963#[cfg(feature = "tokio-1")]
969pub async fn read_v1_msg_async<M: Message, R: tokio::io::AsyncRead + Unpin>(
970 r: &mut AsyncPeekReader<R>,
971) -> Result<(MavHeader, M), MessageReadError> {
972 let message = read_v1_raw_message_async::<M, _>(r).await?;
973
974 Ok((
975 MavHeader {
976 sequence: message.sequence(),
977 system_id: message.system_id(),
978 component_id: message.component_id(),
979 },
980 M::parse(
981 MavlinkVersion::V1,
982 u32::from(message.message_id()),
983 message.payload(),
984 )?,
985 ))
986}
987
988#[cfg(feature = "embedded")]
993pub async fn read_v1_msg_async<M: Message>(
994 r: &mut impl embedded_io_async::Read,
995) -> Result<(MavHeader, M), MessageReadError> {
996 let message = read_v1_raw_message_async::<M>(r).await?;
997
998 Ok((
999 MavHeader {
1000 sequence: message.sequence(),
1001 system_id: message.system_id(),
1002 component_id: message.component_id(),
1003 },
1004 M::parse(
1005 MavlinkVersion::V1,
1006 u32::from(message.message_id()),
1007 message.payload(),
1008 )?,
1009 ))
1010}
1011
1012const MAVLINK_IFLAG_SIGNED: u8 = 0x01;
1013const MAVLINK_SUPPORTED_IFLAGS: u8 = MAVLINK_IFLAG_SIGNED;
1014
1015#[derive(Debug, Copy, Clone, PartialEq, Eq)]
1016pub struct MAVLinkV2MessageRaw([u8; 1 + Self::HEADER_SIZE + 255 + 2 + Self::SIGNATURE_SIZE]);
1021
1022impl Default for MAVLinkV2MessageRaw {
1023 fn default() -> Self {
1024 Self::new()
1025 }
1026}
1027
1028impl MAVLinkV2MessageRaw {
1029 const HEADER_SIZE: usize = 9;
1030 const SIGNATURE_SIZE: usize = 13;
1031
1032 pub const fn new() -> Self {
1034 Self([0; 1 + Self::HEADER_SIZE + 255 + 2 + Self::SIGNATURE_SIZE])
1035 }
1036
1037 pub const fn from_bytes_unparsed(
1041 bytes: [u8; 1 + Self::HEADER_SIZE + 255 + 2 + Self::SIGNATURE_SIZE],
1042 ) -> Self {
1043 Self(bytes)
1044 }
1045
1046 #[inline]
1048 pub fn as_slice(&self) -> &[u8] {
1049 &self.0
1050 }
1051
1052 #[inline]
1054 pub fn as_mut_slice(&mut self) -> &mut [u8] {
1055 &mut self.0
1056 }
1057
1058 #[inline]
1060 pub fn into_inner(self) -> [u8; 1 + Self::HEADER_SIZE + 255 + 2 + Self::SIGNATURE_SIZE] {
1061 self.0
1062 }
1063
1064 #[inline]
1066 pub fn header(&self) -> &[u8] {
1067 &self.0[1..=Self::HEADER_SIZE]
1068 }
1069
1070 #[inline]
1072 fn mut_header(&mut self) -> &mut [u8] {
1073 &mut self.0[1..=Self::HEADER_SIZE]
1074 }
1075
1076 #[inline]
1078 pub fn payload_length(&self) -> u8 {
1079 self.0[1]
1080 }
1081
1082 #[inline]
1086 pub fn incompatibility_flags(&self) -> u8 {
1087 self.0[2]
1088 }
1089
1090 #[inline]
1094 pub fn incompatibility_flags_mut(&mut self) -> &mut u8 {
1095 &mut self.0[2]
1096 }
1097
1098 #[inline]
1100 pub fn compatibility_flags(&self) -> u8 {
1101 self.0[3]
1102 }
1103
1104 #[inline]
1106 pub fn sequence(&self) -> u8 {
1107 self.0[4]
1108 }
1109
1110 #[inline]
1112 pub fn system_id(&self) -> u8 {
1113 self.0[5]
1114 }
1115
1116 #[inline]
1118 pub fn component_id(&self) -> u8 {
1119 self.0[6]
1120 }
1121
1122 #[inline]
1124 pub fn message_id(&self) -> u32 {
1125 u32::from_le_bytes([self.0[7], self.0[8], self.0[9], 0])
1126 }
1127
1128 #[inline]
1130 pub fn payload(&self) -> &[u8] {
1131 let payload_length: usize = self.payload_length().into();
1132 &self.0[(1 + Self::HEADER_SIZE)..(1 + Self::HEADER_SIZE + payload_length)]
1133 }
1134
1135 #[inline]
1137 pub fn checksum(&self) -> u16 {
1138 let payload_length: usize = self.payload_length().into();
1139 u16::from_le_bytes([
1140 self.0[1 + Self::HEADER_SIZE + payload_length],
1141 self.0[1 + Self::HEADER_SIZE + payload_length + 1],
1142 ])
1143 }
1144
1145 #[cfg(feature = "signing")]
1147 #[inline]
1148 pub fn checksum_bytes(&self) -> &[u8] {
1149 let checksum_offset = 1 + Self::HEADER_SIZE + self.payload_length() as usize;
1150 &self.0[checksum_offset..(checksum_offset + 2)]
1151 }
1152
1153 #[cfg(feature = "signing")]
1157 #[inline]
1158 pub fn signature_link_id(&self) -> u8 {
1159 let payload_length: usize = self.payload_length().into();
1160 self.0[1 + Self::HEADER_SIZE + payload_length + 2]
1161 }
1162
1163 #[cfg(feature = "signing")]
1165 #[inline]
1166 pub fn signature_link_id_mut(&mut self) -> &mut u8 {
1167 let payload_length: usize = self.payload_length().into();
1168 &mut self.0[1 + Self::HEADER_SIZE + payload_length + 2]
1169 }
1170
1171 #[cfg(feature = "signing")]
1177 #[inline]
1178 pub fn signature_timestamp(&self) -> u64 {
1179 let mut timestamp_bytes = [0u8; 8];
1180 timestamp_bytes[0..6].copy_from_slice(self.signature_timestamp_bytes());
1181 u64::from_le_bytes(timestamp_bytes)
1182 }
1183
1184 #[cfg(feature = "signing")]
1188 #[inline]
1189 pub fn signature_timestamp_bytes(&self) -> &[u8] {
1190 let payload_length: usize = self.payload_length().into();
1191 let timestamp_start = 1 + Self::HEADER_SIZE + payload_length + 3;
1192 &self.0[timestamp_start..(timestamp_start + 6)]
1193 }
1194
1195 #[cfg(feature = "signing")]
1197 #[inline]
1198 pub fn signature_timestamp_bytes_mut(&mut self) -> &mut [u8] {
1199 let payload_length: usize = self.payload_length().into();
1200 let timestamp_start = 1 + Self::HEADER_SIZE + payload_length + 3;
1201 &mut self.0[timestamp_start..(timestamp_start + 6)]
1202 }
1203
1204 #[cfg(feature = "signing")]
1208 #[inline]
1209 pub fn signature_value(&self) -> &[u8] {
1210 let payload_length: usize = self.payload_length().into();
1211 let signature_start = 1 + Self::HEADER_SIZE + payload_length + 3 + 6;
1212 &self.0[signature_start..(signature_start + 6)]
1213 }
1214
1215 #[cfg(feature = "signing")]
1217 #[inline]
1218 pub fn signature_value_mut(&mut self) -> &mut [u8] {
1219 let payload_length: usize = self.payload_length().into();
1220 let signature_start = 1 + Self::HEADER_SIZE + payload_length + 3 + 6;
1221 &mut self.0[signature_start..(signature_start + 6)]
1222 }
1223
1224 fn mut_payload_and_checksum_and_sign(&mut self) -> &mut [u8] {
1225 let payload_length: usize = self.payload_length().into();
1226
1227 let signature_size = if (self.incompatibility_flags() & MAVLINK_IFLAG_SIGNED) == 0 {
1229 0
1230 } else {
1231 Self::SIGNATURE_SIZE
1232 };
1233
1234 &mut self.0
1235 [(1 + Self::HEADER_SIZE)..(1 + Self::HEADER_SIZE + payload_length + signature_size + 2)]
1236 }
1237
1238 #[inline]
1240 pub fn has_valid_crc<M: Message>(&self) -> bool {
1241 let payload_length: usize = self.payload_length().into();
1242 self.checksum()
1243 == calculate_crc(
1244 &self.0[1..(1 + Self::HEADER_SIZE + payload_length)],
1245 M::extra_crc(self.message_id()),
1246 )
1247 }
1248
1249 #[cfg(feature = "signing")]
1253 pub fn calculate_signature(&self, secret_key: &[u8], target_buffer: &mut [u8; 6]) {
1254 let mut hasher = Sha256::new();
1255 hasher.update(secret_key);
1256 hasher.update([MAV_STX_V2]);
1257 hasher.update(self.header());
1258 hasher.update(self.payload());
1259 hasher.update(self.checksum_bytes());
1260 hasher.update([self.signature_link_id()]);
1261 hasher.update(self.signature_timestamp_bytes());
1262 target_buffer.copy_from_slice(&hasher.finalize()[0..6]);
1263 }
1264
1265 pub fn raw_bytes(&self) -> &[u8] {
1267 let payload_length = self.payload_length() as usize;
1268
1269 let signature_size = if (self.incompatibility_flags() & MAVLINK_IFLAG_SIGNED) == 0 {
1270 0
1271 } else {
1272 Self::SIGNATURE_SIZE
1273 };
1274
1275 &self.0[..(1 + Self::HEADER_SIZE + payload_length + signature_size + 2)]
1276 }
1277
1278 fn serialize_stx_and_header_and_crc(
1279 &mut self,
1280 header: MavHeader,
1281 msgid: u32,
1282 payload_length: usize,
1283 extra_crc: u8,
1284 incompat_flags: u8,
1285 ) {
1286 self.0[0] = MAV_STX_V2;
1287 let msgid_bytes = msgid.to_le_bytes();
1288
1289 let header_buf = self.mut_header();
1290 header_buf.copy_from_slice(&[
1291 payload_length as u8,
1292 incompat_flags,
1293 0, header.sequence,
1295 header.system_id,
1296 header.component_id,
1297 msgid_bytes[0],
1298 msgid_bytes[1],
1299 msgid_bytes[2],
1300 ]);
1301
1302 let crc = calculate_crc(
1303 &self.0[1..(1 + Self::HEADER_SIZE + payload_length)],
1304 extra_crc,
1305 );
1306 self.0[(1 + Self::HEADER_SIZE + payload_length)
1307 ..(1 + Self::HEADER_SIZE + payload_length + 2)]
1308 .copy_from_slice(&crc.to_le_bytes());
1309 }
1310
1311 pub fn serialize_message<M: Message>(&mut self, header: MavHeader, message: &M) {
1315 let payload_buf = &mut self.0[(1 + Self::HEADER_SIZE)..(1 + Self::HEADER_SIZE + 255)];
1316 let payload_length = message.ser(MavlinkVersion::V2, payload_buf);
1317
1318 let message_id = message.message_id();
1319 self.serialize_stx_and_header_and_crc(
1320 header,
1321 message_id,
1322 payload_length,
1323 M::extra_crc(message_id),
1324 0,
1325 );
1326 }
1327
1328 pub fn serialize_message_for_signing<M: Message>(&mut self, header: MavHeader, message: &M) {
1333 let payload_buf = &mut self.0[(1 + Self::HEADER_SIZE)..(1 + Self::HEADER_SIZE + 255)];
1334 let payload_length = message.ser(MavlinkVersion::V2, payload_buf);
1335
1336 let message_id = message.message_id();
1337 self.serialize_stx_and_header_and_crc(
1338 header,
1339 message_id,
1340 payload_length,
1341 M::extra_crc(message_id),
1342 MAVLINK_IFLAG_SIGNED,
1343 );
1344 }
1345
1346 pub fn serialize_message_data<D: MessageData>(&mut self, header: MavHeader, message_data: &D) {
1347 let payload_buf = &mut self.0[(1 + Self::HEADER_SIZE)..(1 + Self::HEADER_SIZE + 255)];
1348 let payload_length = message_data.ser(MavlinkVersion::V2, payload_buf);
1349
1350 self.serialize_stx_and_header_and_crc(header, D::ID, payload_length, D::EXTRA_CRC, 0);
1351 }
1352}
1353
1354#[allow(unused_variables)]
1355fn try_decode_v2<M: Message, R: Read>(
1356 reader: &mut PeekReader<R>,
1357 signing_data: Option<&SigningData>,
1358) -> Result<Option<MAVLinkV2MessageRaw>, MessageReadError> {
1359 let mut message = MAVLinkV2MessageRaw::new();
1360 let whole_header_size = MAVLinkV2MessageRaw::HEADER_SIZE + 1;
1361
1362 message.0[0] = MAV_STX_V2;
1363 let header = &reader.peek_exact(whole_header_size)?[1..whole_header_size];
1364 message.mut_header().copy_from_slice(header);
1365
1366 if message.incompatibility_flags() & !MAVLINK_SUPPORTED_IFLAGS > 0 {
1367 reader.consume(1);
1369 return Ok(None);
1370 }
1371
1372 let packet_length = message.raw_bytes().len();
1373 let payload_and_checksum_and_sign =
1374 &reader.peek_exact(packet_length)?[whole_header_size..packet_length];
1375 message
1376 .mut_payload_and_checksum_and_sign()
1377 .copy_from_slice(payload_and_checksum_and_sign);
1378
1379 if message.has_valid_crc::<M>() {
1380 reader.consume(message.raw_bytes().len());
1382 } else {
1383 reader.consume(1);
1384 return Ok(None);
1385 }
1386
1387 #[cfg(feature = "signing")]
1388 if let Some(signing_data) = signing_data {
1389 if !signing_data.verify_signature(&message) {
1390 return Ok(None);
1391 }
1392 }
1393
1394 Ok(Some(message))
1395}
1396
1397#[cfg(feature = "tokio-1")]
1398#[allow(unused_variables)]
1399async fn try_decode_v2_async<M: Message, R: tokio::io::AsyncRead + Unpin>(
1401 reader: &mut AsyncPeekReader<R>,
1402 signing_data: Option<&SigningData>,
1403) -> Result<Option<MAVLinkV2MessageRaw>, MessageReadError> {
1404 let mut message = MAVLinkV2MessageRaw::new();
1405
1406 message.0[0] = MAV_STX_V2;
1407 let header = &reader.peek_exact(MAVLinkV2MessageRaw::HEADER_SIZE).await?
1408 [..MAVLinkV2MessageRaw::HEADER_SIZE];
1409 message.mut_header().copy_from_slice(header);
1410
1411 if message.incompatibility_flags() & !MAVLINK_SUPPORTED_IFLAGS > 0 {
1412 return Ok(None);
1414 }
1415
1416 let packet_length = message.raw_bytes().len() - 1;
1417 let payload_and_checksum_and_sign =
1418 &reader.peek_exact(packet_length).await?[MAVLinkV2MessageRaw::HEADER_SIZE..packet_length];
1419 message
1420 .mut_payload_and_checksum_and_sign()
1421 .copy_from_slice(payload_and_checksum_and_sign);
1422
1423 if message.has_valid_crc::<M>() {
1424 reader.consume(message.raw_bytes().len() - 1);
1426 } else {
1427 return Ok(None);
1428 }
1429
1430 #[cfg(feature = "signing")]
1431 if let Some(signing_data) = signing_data {
1432 if !signing_data.verify_signature(&message) {
1433 return Ok(None);
1434 }
1435 }
1436
1437 Ok(Some(message))
1438}
1439
1440#[inline]
1446pub fn read_v2_raw_message<M: Message, R: Read>(
1447 reader: &mut PeekReader<R>,
1448) -> Result<MAVLinkV2MessageRaw, MessageReadError> {
1449 read_v2_raw_message_inner::<M, R>(reader, None)
1450}
1451
1452#[cfg(feature = "signing")]
1458#[inline]
1459pub fn read_v2_raw_message_signed<M: Message, R: Read>(
1460 reader: &mut PeekReader<R>,
1461 signing_data: Option<&SigningData>,
1462) -> Result<MAVLinkV2MessageRaw, MessageReadError> {
1463 read_v2_raw_message_inner::<M, R>(reader, signing_data)
1464}
1465
1466#[allow(unused_variables)]
1467fn read_v2_raw_message_inner<M: Message, R: Read>(
1468 reader: &mut PeekReader<R>,
1469 signing_data: Option<&SigningData>,
1470) -> Result<MAVLinkV2MessageRaw, MessageReadError> {
1471 loop {
1472 while reader.peek_exact(1)?[0] != MAV_STX_V2 {
1474 reader.consume(1);
1475 }
1476
1477 if let Some(message) = try_decode_v2::<M, _>(reader, signing_data)? {
1478 return Ok(message);
1479 }
1480 }
1481}
1482
1483#[cfg(feature = "tokio-1")]
1489pub async fn read_v2_raw_message_async<M: Message, R: tokio::io::AsyncRead + Unpin>(
1490 reader: &mut AsyncPeekReader<R>,
1491) -> Result<MAVLinkV2MessageRaw, MessageReadError> {
1492 read_v2_raw_message_async_inner::<M, R>(reader, None).await
1493}
1494
1495#[cfg(feature = "tokio-1")]
1496#[allow(unused_variables)]
1497async fn read_v2_raw_message_async_inner<M: Message, R: tokio::io::AsyncRead + Unpin>(
1498 reader: &mut AsyncPeekReader<R>,
1499 signing_data: Option<&SigningData>,
1500) -> Result<MAVLinkV2MessageRaw, MessageReadError> {
1501 loop {
1502 loop {
1503 if reader.read_u8().await? == MAV_STX_V2 {
1505 break;
1506 }
1507 }
1508
1509 if let Some(message) = try_decode_v2_async::<M, _>(reader, signing_data).await? {
1510 return Ok(message);
1511 }
1512 }
1513}
1514
1515#[cfg(all(feature = "tokio-1", feature = "signing"))]
1521pub async fn read_v2_raw_message_async_signed<M: Message, R: tokio::io::AsyncRead + Unpin>(
1522 reader: &mut AsyncPeekReader<R>,
1523 signing_data: Option<&SigningData>,
1524) -> Result<MAVLinkV2MessageRaw, MessageReadError> {
1525 read_v2_raw_message_async_inner::<M, R>(reader, signing_data).await
1526}
1527
1528#[cfg(feature = "embedded")]
1534pub async fn read_v2_raw_message_async<M: Message>(
1535 reader: &mut impl embedded_io_async::Read,
1536) -> Result<MAVLinkV2MessageRaw, MessageReadError> {
1537 loop {
1538 let mut byte = [0u8];
1540 loop {
1541 reader
1542 .read_exact(&mut byte)
1543 .await
1544 .map_err(|_| MessageReadError::Io)?;
1545 if byte[0] == MAV_STX_V2 {
1546 break;
1547 }
1548 }
1549
1550 let mut message = MAVLinkV2MessageRaw::new();
1551
1552 message.0[0] = MAV_STX_V2;
1553 reader
1554 .read_exact(message.mut_header())
1555 .await
1556 .map_err(|_| MessageReadError::Io)?;
1557
1558 if message.incompatibility_flags() & !MAVLINK_SUPPORTED_IFLAGS > 0 {
1559 continue;
1561 }
1562
1563 reader
1564 .read_exact(message.mut_payload_and_checksum_and_sign())
1565 .await
1566 .map_err(|_| MessageReadError::Io)?;
1567
1568 if message.has_valid_crc::<M>() {
1571 return Ok(message);
1572 }
1573 }
1574}
1575
1576#[inline]
1582pub fn read_v2_msg<M: Message, R: Read>(
1583 read: &mut PeekReader<R>,
1584) -> Result<(MavHeader, M), MessageReadError> {
1585 read_v2_msg_inner(read, None)
1586}
1587
1588#[cfg(feature = "signing")]
1594#[inline]
1595pub fn read_v2_msg_signed<M: Message, R: Read>(
1596 read: &mut PeekReader<R>,
1597 signing_data: Option<&SigningData>,
1598) -> Result<(MavHeader, M), MessageReadError> {
1599 read_v2_msg_inner(read, signing_data)
1600}
1601
1602fn read_v2_msg_inner<M: Message, R: Read>(
1603 read: &mut PeekReader<R>,
1604 signing_data: Option<&SigningData>,
1605) -> Result<(MavHeader, M), MessageReadError> {
1606 let message = read_v2_raw_message_inner::<M, _>(read, signing_data)?;
1607
1608 Ok((
1609 MavHeader {
1610 sequence: message.sequence(),
1611 system_id: message.system_id(),
1612 component_id: message.component_id(),
1613 },
1614 M::parse(MavlinkVersion::V2, message.message_id(), message.payload())?,
1615 ))
1616}
1617
1618#[cfg(feature = "tokio-1")]
1624pub async fn read_v2_msg_async<M: Message, R: tokio::io::AsyncRead + Unpin>(
1625 read: &mut AsyncPeekReader<R>,
1626) -> Result<(MavHeader, M), MessageReadError> {
1627 read_v2_msg_async_inner(read, None).await
1628}
1629
1630#[cfg(all(feature = "tokio-1", feature = "signing"))]
1636pub async fn read_v2_msg_async_signed<M: Message, R: tokio::io::AsyncRead + Unpin>(
1637 read: &mut AsyncPeekReader<R>,
1638 signing_data: Option<&SigningData>,
1639) -> Result<(MavHeader, M), MessageReadError> {
1640 read_v2_msg_async_inner(read, signing_data).await
1641}
1642
1643#[cfg(feature = "tokio-1")]
1644async fn read_v2_msg_async_inner<M: Message, R: tokio::io::AsyncRead + Unpin>(
1645 read: &mut AsyncPeekReader<R>,
1646 signing_data: Option<&SigningData>,
1647) -> Result<(MavHeader, M), MessageReadError> {
1648 let message = read_v2_raw_message_async_inner::<M, _>(read, signing_data).await?;
1649
1650 Ok((
1651 MavHeader {
1652 sequence: message.sequence(),
1653 system_id: message.system_id(),
1654 component_id: message.component_id(),
1655 },
1656 M::parse(MavlinkVersion::V2, message.message_id(), message.payload())?,
1657 ))
1658}
1659
1660#[cfg(feature = "embedded")]
1665pub async fn read_v2_msg_async<M: Message, R: embedded_io_async::Read>(
1666 r: &mut R,
1667) -> Result<(MavHeader, M), MessageReadError> {
1668 let message = read_v2_raw_message_async::<M>(r).await?;
1669
1670 Ok((
1671 MavHeader {
1672 sequence: message.sequence(),
1673 system_id: message.system_id(),
1674 component_id: message.component_id(),
1675 },
1676 M::parse(
1677 MavlinkVersion::V2,
1678 u32::from(message.message_id()),
1679 message.payload(),
1680 )?,
1681 ))
1682}
1683
1684pub enum MAVLinkMessageRaw {
1686 V1(MAVLinkV1MessageRaw),
1687 V2(MAVLinkV2MessageRaw),
1688}
1689
1690impl MAVLinkMessageRaw {
1691 pub fn payload(&self) -> &[u8] {
1692 match self {
1693 Self::V1(msg) => msg.payload(),
1694 Self::V2(msg) => msg.payload(),
1695 }
1696 }
1697 pub fn sequence(&self) -> u8 {
1698 match self {
1699 Self::V1(msg) => msg.sequence(),
1700 Self::V2(msg) => msg.sequence(),
1701 }
1702 }
1703 pub fn system_id(&self) -> u8 {
1704 match self {
1705 Self::V1(msg) => msg.system_id(),
1706 Self::V2(msg) => msg.system_id(),
1707 }
1708 }
1709 pub fn component_id(&self) -> u8 {
1710 match self {
1711 Self::V1(msg) => msg.component_id(),
1712 Self::V2(msg) => msg.component_id(),
1713 }
1714 }
1715 pub fn message_id(&self) -> u32 {
1716 match self {
1717 Self::V1(msg) => u32::from(msg.message_id()),
1718 Self::V2(msg) => msg.message_id(),
1719 }
1720 }
1721 pub fn version(&self) -> MavlinkVersion {
1722 match self {
1723 Self::V1(_) => MavlinkVersion::V1,
1724 Self::V2(_) => MavlinkVersion::V2,
1725 }
1726 }
1727}
1728
1729#[inline]
1735pub fn read_any_raw_message<M: Message, R: Read>(
1736 reader: &mut PeekReader<R>,
1737) -> Result<MAVLinkMessageRaw, MessageReadError> {
1738 read_any_raw_message_inner::<M, R>(reader, None)
1739}
1740
1741#[cfg(feature = "signing")]
1747#[inline]
1748pub fn read_any_raw_message_signed<M: Message, R: Read>(
1749 reader: &mut PeekReader<R>,
1750 signing_data: Option<&SigningData>,
1751) -> Result<MAVLinkMessageRaw, MessageReadError> {
1752 read_any_raw_message_inner::<M, R>(reader, signing_data)
1753}
1754
1755#[allow(unused_variables)]
1756fn read_any_raw_message_inner<M: Message, R: Read>(
1757 reader: &mut PeekReader<R>,
1758 signing_data: Option<&SigningData>,
1759) -> Result<MAVLinkMessageRaw, MessageReadError> {
1760 loop {
1761 let version = loop {
1763 let byte = reader.peek_exact(1)?[0];
1764 if byte == MAV_STX {
1765 break MavlinkVersion::V1;
1766 }
1767 if byte == MAV_STX_V2 {
1768 break MavlinkVersion::V2;
1769 }
1770 reader.consume(1);
1771 };
1772 match version {
1773 MavlinkVersion::V1 => {
1774 if let Some(message) = try_decode_v1::<M, _>(reader)? {
1775 #[cfg(feature = "signing")]
1777 if let Some(signing) = signing_data {
1778 if signing.config.allow_unsigned {
1779 return Ok(MAVLinkMessageRaw::V1(message));
1780 }
1781 } else {
1782 return Ok(MAVLinkMessageRaw::V1(message));
1783 }
1784 #[cfg(not(feature = "signing"))]
1785 return Ok(MAVLinkMessageRaw::V1(message));
1786 }
1787
1788 reader.consume(1);
1789 }
1790 MavlinkVersion::V2 => {
1791 if let Some(message) = try_decode_v2::<M, _>(reader, signing_data)? {
1792 return Ok(MAVLinkMessageRaw::V2(message));
1793 }
1794 }
1795 }
1796 }
1797}
1798
1799#[cfg(feature = "tokio-1")]
1805pub async fn read_any_raw_message_async<M: Message, R: tokio::io::AsyncRead + Unpin>(
1806 reader: &mut AsyncPeekReader<R>,
1807) -> Result<MAVLinkMessageRaw, MessageReadError> {
1808 read_any_raw_message_async_inner::<M, R>(reader, None).await
1809}
1810
1811#[cfg(all(feature = "tokio-1", feature = "signing"))]
1819pub async fn read_any_raw_message_async_signed<M: Message, R: tokio::io::AsyncRead + Unpin>(
1820 reader: &mut AsyncPeekReader<R>,
1821 signing_data: Option<&SigningData>,
1822) -> Result<MAVLinkMessageRaw, MessageReadError> {
1823 read_any_raw_message_async_inner::<M, R>(reader, signing_data).await
1824}
1825
1826#[cfg(feature = "tokio-1")]
1827#[allow(unused_variables)]
1828async fn read_any_raw_message_async_inner<M: Message, R: tokio::io::AsyncRead + Unpin>(
1829 reader: &mut AsyncPeekReader<R>,
1830 signing_data: Option<&SigningData>,
1831) -> Result<MAVLinkMessageRaw, MessageReadError> {
1832 loop {
1833 let version = loop {
1835 let read = reader.read_u8().await?;
1836 if read == MAV_STX {
1837 break MavlinkVersion::V1;
1838 }
1839 if read == MAV_STX_V2 {
1840 break MavlinkVersion::V2;
1841 }
1842 };
1843
1844 match version {
1845 MavlinkVersion::V1 => {
1846 if let Some(message) = try_decode_v1_async::<M, _>(reader).await? {
1847 #[cfg(feature = "signing")]
1849 if let Some(signing) = signing_data {
1850 if signing.config.allow_unsigned {
1851 return Ok(MAVLinkMessageRaw::V1(message));
1852 }
1853 } else {
1854 return Ok(MAVLinkMessageRaw::V1(message));
1855 }
1856 #[cfg(not(feature = "signing"))]
1857 return Ok(MAVLinkMessageRaw::V1(message));
1858 }
1859 }
1860 MavlinkVersion::V2 => {
1861 if let Some(message) = try_decode_v2_async::<M, _>(reader, signing_data).await? {
1862 return Ok(MAVLinkMessageRaw::V2(message));
1863 }
1864 }
1865 }
1866 }
1867}
1868
1869#[inline]
1875pub fn read_any_msg<M: Message, R: Read>(
1876 read: &mut PeekReader<R>,
1877) -> Result<(MavHeader, M), MessageReadError> {
1878 read_any_msg_inner(read, None)
1879}
1880
1881#[cfg(feature = "signing")]
1889#[inline]
1890pub fn read_any_msg_signed<M: Message, R: Read>(
1891 read: &mut PeekReader<R>,
1892 signing_data: Option<&SigningData>,
1893) -> Result<(MavHeader, M), MessageReadError> {
1894 read_any_msg_inner(read, signing_data)
1895}
1896
1897fn read_any_msg_inner<M: Message, R: Read>(
1898 read: &mut PeekReader<R>,
1899 signing_data: Option<&SigningData>,
1900) -> Result<(MavHeader, M), MessageReadError> {
1901 let message = read_any_raw_message_inner::<M, _>(read, signing_data)?;
1902 Ok((
1903 MavHeader {
1904 sequence: message.sequence(),
1905 system_id: message.system_id(),
1906 component_id: message.component_id(),
1907 },
1908 M::parse(message.version(), message.message_id(), message.payload())?,
1909 ))
1910}
1911
1912#[cfg(feature = "tokio-1")]
1918pub async fn read_any_msg_async<M: Message, R: tokio::io::AsyncRead + Unpin>(
1919 read: &mut AsyncPeekReader<R>,
1920) -> Result<(MavHeader, M), MessageReadError> {
1921 read_any_msg_async_inner(read, None).await
1922}
1923
1924#[cfg(all(feature = "tokio-1", feature = "signing"))]
1932#[inline]
1933pub async fn read_any_msg_async_signed<M: Message, R: tokio::io::AsyncRead + Unpin>(
1934 read: &mut AsyncPeekReader<R>,
1935 signing_data: Option<&SigningData>,
1936) -> Result<(MavHeader, M), MessageReadError> {
1937 read_any_msg_async_inner(read, signing_data).await
1938}
1939
1940#[cfg(feature = "tokio-1")]
1941async fn read_any_msg_async_inner<M: Message, R: tokio::io::AsyncRead + Unpin>(
1942 read: &mut AsyncPeekReader<R>,
1943 signing_data: Option<&SigningData>,
1944) -> Result<(MavHeader, M), MessageReadError> {
1945 let message = read_any_raw_message_async_inner::<M, _>(read, signing_data).await?;
1946
1947 Ok((
1948 MavHeader {
1949 sequence: message.sequence(),
1950 system_id: message.system_id(),
1951 component_id: message.component_id(),
1952 },
1953 M::parse(message.version(), message.message_id(), message.payload())?,
1954 ))
1955}
1956
1957pub fn write_versioned_msg<M: Message, W: Write>(
1963 w: &mut W,
1964 version: MavlinkVersion,
1965 header: MavHeader,
1966 data: &M,
1967) -> Result<usize, MessageWriteError> {
1968 match version {
1969 MavlinkVersion::V2 => write_v2_msg(w, header, data),
1970 MavlinkVersion::V1 => write_v1_msg(w, header, data),
1971 }
1972}
1973
1974#[cfg(feature = "signing")]
1982pub fn write_versioned_msg_signed<M: Message, W: Write>(
1983 w: &mut W,
1984 version: MavlinkVersion,
1985 header: MavHeader,
1986 data: &M,
1987 signing_data: Option<&SigningData>,
1988) -> Result<usize, MessageWriteError> {
1989 match version {
1990 MavlinkVersion::V2 => write_v2_msg_signed(w, header, data, signing_data),
1991 MavlinkVersion::V1 => write_v1_msg(w, header, data),
1992 }
1993}
1994
1995#[cfg(feature = "tokio-1")]
2001pub async fn write_versioned_msg_async<M: Message, W: AsyncWrite + Unpin>(
2002 w: &mut W,
2003 version: MavlinkVersion,
2004 header: MavHeader,
2005 data: &M,
2006) -> Result<usize, MessageWriteError> {
2007 match version {
2008 MavlinkVersion::V2 => write_v2_msg_async(w, header, data).await,
2009 MavlinkVersion::V1 => write_v1_msg_async(w, header, data).await,
2010 }
2011}
2012
2013#[cfg(all(feature = "tokio-1", feature = "signing"))]
2021pub async fn write_versioned_msg_async_signed<M: Message, W: AsyncWrite + Unpin>(
2022 w: &mut W,
2023 version: MavlinkVersion,
2024 header: MavHeader,
2025 data: &M,
2026 signing_data: Option<&SigningData>,
2027) -> Result<usize, MessageWriteError> {
2028 match version {
2029 MavlinkVersion::V2 => write_v2_msg_async_signed(w, header, data, signing_data).await,
2030 MavlinkVersion::V1 => write_v1_msg_async(w, header, data).await,
2031 }
2032}
2033
2034#[cfg(feature = "embedded")]
2039pub async fn write_versioned_msg_async<M: Message>(
2040 w: &mut impl embedded_io_async::Write,
2041 version: MavlinkVersion,
2042 header: MavHeader,
2043 data: &M,
2044) -> Result<usize, MessageWriteError> {
2045 match version {
2046 MavlinkVersion::V2 => write_v2_msg_async(w, header, data).await,
2047 MavlinkVersion::V1 => write_v1_msg_async(w, header, data).await,
2048 }
2049}
2050
2051pub fn write_v2_msg<M: Message, W: Write>(
2057 w: &mut W,
2058 header: MavHeader,
2059 data: &M,
2060) -> Result<usize, MessageWriteError> {
2061 let mut message_raw = MAVLinkV2MessageRaw::new();
2062 message_raw.serialize_message(header, data);
2063
2064 let payload_length: usize = message_raw.payload_length().into();
2065 let len = 1 + MAVLinkV2MessageRaw::HEADER_SIZE + payload_length + 2;
2066
2067 w.write_all(&message_raw.0[..len])?;
2068
2069 Ok(len)
2070}
2071
2072#[cfg(feature = "signing")]
2078pub fn write_v2_msg_signed<M: Message, W: Write>(
2079 w: &mut W,
2080 header: MavHeader,
2081 data: &M,
2082 signing_data: Option<&SigningData>,
2083) -> Result<usize, MessageWriteError> {
2084 let mut message_raw = MAVLinkV2MessageRaw::new();
2085
2086 let signature_len = if let Some(signing_data) = signing_data {
2087 if signing_data.config.sign_outgoing {
2088 message_raw.serialize_message_for_signing(header, data);
2089 signing_data.sign_message(&mut message_raw);
2090 MAVLinkV2MessageRaw::SIGNATURE_SIZE
2091 } else {
2092 message_raw.serialize_message(header, data);
2093 0
2094 }
2095 } else {
2096 message_raw.serialize_message(header, data);
2097 0
2098 };
2099
2100 let payload_length: usize = message_raw.payload_length().into();
2101 let len = 1 + MAVLinkV2MessageRaw::HEADER_SIZE + payload_length + 2 + signature_len;
2102
2103 w.write_all(&message_raw.0[..len])?;
2104
2105 Ok(len)
2106}
2107
2108#[cfg(feature = "tokio-1")]
2114pub async fn write_v2_msg_async<M: Message, W: AsyncWrite + Unpin>(
2115 w: &mut W,
2116 header: MavHeader,
2117 data: &M,
2118) -> Result<usize, MessageWriteError> {
2119 let mut message_raw = MAVLinkV2MessageRaw::new();
2120 message_raw.serialize_message(header, data);
2121
2122 let payload_length: usize = message_raw.payload_length().into();
2123 let len = 1 + MAVLinkV2MessageRaw::HEADER_SIZE + payload_length + 2;
2124
2125 w.write_all(&message_raw.0[..len]).await?;
2126
2127 Ok(len)
2128}
2129
2130#[cfg(feature = "signing")]
2136#[cfg(feature = "tokio-1")]
2137pub async fn write_v2_msg_async_signed<M: Message, W: AsyncWrite + Unpin>(
2138 w: &mut W,
2139 header: MavHeader,
2140 data: &M,
2141 signing_data: Option<&SigningData>,
2142) -> Result<usize, MessageWriteError> {
2143 let mut message_raw = MAVLinkV2MessageRaw::new();
2144
2145 let signature_len = if let Some(signing_data) = signing_data {
2146 if signing_data.config.sign_outgoing {
2147 message_raw.serialize_message_for_signing(header, data);
2148 signing_data.sign_message(&mut message_raw);
2149 MAVLinkV2MessageRaw::SIGNATURE_SIZE
2150 } else {
2151 message_raw.serialize_message(header, data);
2152 0
2153 }
2154 } else {
2155 message_raw.serialize_message(header, data);
2156 0
2157 };
2158
2159 let payload_length: usize = message_raw.payload_length().into();
2160 let len = 1 + MAVLinkV2MessageRaw::HEADER_SIZE + payload_length + 2 + signature_len;
2161
2162 w.write_all(&message_raw.0[..len]).await?;
2163
2164 Ok(len)
2165}
2166
2167#[cfg(feature = "embedded")]
2176pub async fn write_v2_msg_async<M: Message>(
2177 w: &mut impl embedded_io_async::Write,
2178 header: MavHeader,
2179 data: &M,
2180) -> Result<usize, MessageWriteError> {
2181 let mut message_raw = MAVLinkV2MessageRaw::new();
2182 message_raw.serialize_message(header, data);
2183
2184 let payload_length: usize = message_raw.payload_length().into();
2185 let len = 1 + MAVLinkV2MessageRaw::HEADER_SIZE + payload_length + 2;
2186
2187 w.write_all(&message_raw.0[..len])
2188 .await
2189 .map_err(|_| MessageWriteError::Io)?;
2190
2191 Ok(len)
2192}
2193
2194pub fn write_v1_msg<M: Message, W: Write>(
2200 w: &mut W,
2201 header: MavHeader,
2202 data: &M,
2203) -> Result<usize, MessageWriteError> {
2204 if data.message_id() > u8::MAX.into() {
2205 return Err(MessageWriteError::MAVLink2Only);
2206 }
2207 let mut message_raw = MAVLinkV1MessageRaw::new();
2208 message_raw.serialize_message(header, data);
2209
2210 let payload_length: usize = message_raw.payload_length().into();
2211 let len = 1 + MAVLinkV1MessageRaw::HEADER_SIZE + payload_length + 2;
2212
2213 w.write_all(&message_raw.0[..len])?;
2214
2215 Ok(len)
2216}
2217
2218#[cfg(feature = "tokio-1")]
2224pub async fn write_v1_msg_async<M: Message, W: AsyncWrite + Unpin>(
2225 w: &mut W,
2226 header: MavHeader,
2227 data: &M,
2228) -> Result<usize, MessageWriteError> {
2229 if data.message_id() > u8::MAX.into() {
2230 return Err(MessageWriteError::MAVLink2Only);
2231 }
2232 let mut message_raw = MAVLinkV1MessageRaw::new();
2233 message_raw.serialize_message(header, data);
2234
2235 let payload_length: usize = message_raw.payload_length().into();
2236 let len = 1 + MAVLinkV1MessageRaw::HEADER_SIZE + payload_length + 2;
2237
2238 w.write_all(&message_raw.0[..len]).await?;
2239
2240 Ok(len)
2241}
2242
2243#[cfg(feature = "embedded")]
2248pub async fn write_v1_msg_async<M: Message>(
2249 w: &mut impl embedded_io_async::Write,
2250 header: MavHeader,
2251 data: &M,
2252) -> Result<usize, MessageWriteError> {
2253 if data.message_id() > u8::MAX.into() {
2254 return Err(MessageWriteError::MAVLink2Only);
2255 }
2256 let mut message_raw = MAVLinkV1MessageRaw::new();
2257 message_raw.serialize_message(header, data);
2258
2259 let payload_length: usize = message_raw.payload_length().into();
2260 let len = 1 + MAVLinkV1MessageRaw::HEADER_SIZE + payload_length + 2;
2261
2262 w.write_all(&message_raw.0[..len])
2263 .await
2264 .map_err(|_| MessageWriteError::Io)?;
2265
2266 Ok(len)
2267}
2268
2269#[deprecated = "use read_versioned_raw_message instead"]
2270pub fn read_raw_versioned_msg<M: Message, R: Read>(
2271 r: &mut PeekReader<R>,
2272 version: ReadVersion,
2273) -> Result<MAVLinkMessageRaw, MessageReadError> {
2274 read_versioned_raw_message::<M, _>(r, version)
2275}
2276
2277#[cfg(feature = "tokio-1")]
2278#[deprecated = "use read_versioned_raw_message_async instead"]
2279pub async fn read_raw_versioned_msg_async<M: Message, R: tokio::io::AsyncRead + Unpin>(
2280 r: &mut AsyncPeekReader<R>,
2281 version: ReadVersion,
2282) -> Result<MAVLinkMessageRaw, MessageReadError> {
2283 read_versioned_raw_message_async::<M, _>(r, version).await
2284}
2285
2286#[cfg(feature = "signing")]
2287#[deprecated = "use read_versioned_raw_message_signed instead"]
2288pub fn read_raw_versioned_msg_signed<M: Message, R: Read>(
2289 r: &mut PeekReader<R>,
2290 version: ReadVersion,
2291 signing_data: Option<&SigningData>,
2292) -> Result<MAVLinkMessageRaw, MessageReadError> {
2293 read_versioned_raw_message_signed::<M, _>(r, version, signing_data)
2294}
2295
2296#[cfg(all(feature = "tokio-1", feature = "signing"))]
2297#[deprecated = "use read_versioned_raw_message_async_signed instead"]
2298pub async fn read_raw_versioned_msg_async_signed<M: Message, R: tokio::io::AsyncRead + Unpin>(
2299 r: &mut AsyncPeekReader<R>,
2300 version: ReadVersion,
2301 signing_data: Option<&SigningData>,
2302) -> Result<MAVLinkMessageRaw, MessageReadError> {
2303 read_versioned_raw_message_async_signed::<M, _>(r, version, signing_data).await
2304}