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(any(feature = "std", feature = "tokio"))]
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")]
121pub use self::connection::{AsyncConnectable, AsyncMavConnection, connect_async};
122
123#[cfg(feature = "tokio")]
124pub mod async_peek_reader;
125#[cfg(feature = "tokio")]
126use async_peek_reader::AsyncPeekReader;
127#[cfg(feature = "tokio")]
128use tokio::io::{AsyncWrite, AsyncWriteExt};
129
130#[cfg(all(feature = "embedded", not(feature = "std")))]
131pub mod embedded;
132#[cfg(all(feature = "embedded", not(feature = "std")))]
133use embedded::{Read, Write};
134
135#[cfg(not(feature = "mav2-message-signing"))]
136type SigningData = ();
137#[cfg(feature = "mav2-message-signing")]
138mod signing;
139#[cfg(feature = "mav2-message-signing")]
140pub use self::signing::{SigningConfig, SigningData};
141#[cfg(feature = "mav2-message-signing")]
142use sha2::{Digest, Sha256};
143
144#[cfg(feature = "arbitrary")]
145use arbitrary::Arbitrary;
146
147#[cfg(any(feature = "std", feature = "tokio"))]
148mod connectable;
149
150#[cfg(any(feature = "std", feature = "tokio"))]
151mod connection_shared;
152
153#[cfg(any(feature = "std", feature = "tokio"))]
154pub use connectable::ConnectionAddress;
155
156#[cfg(feature = "transport-direct-serial")]
157pub use connection::direct_serial::config::SerialConfig;
158
159#[cfg(feature = "transport-tcp")]
160pub use connection::tcp::config::{TcpConfig, TcpMode};
161
162#[cfg(feature = "transport-udp")]
163pub use connection::udp::config::{UdpConfig, UdpMode};
164
165#[cfg(feature = "std")]
166pub use connection::file::config::FileConfig;
167
168pub const MAX_FRAME_SIZE: usize = 280;
172
173pub trait Message
178where
179 Self: Sized,
180{
181 fn message_id(&self) -> u32;
183
184 fn message_name(&self) -> &'static str;
186
187 fn target_system_id(&self) -> Option<u8>;
189
190 fn target_component_id(&self) -> Option<u8>;
192
193 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize;
199
200 fn parse(version: MavlinkVersion, msgid: u32, payload: &[u8]) -> Result<Self, ParserError>;
209
210 fn message_id_from_name(name: &str) -> Option<u32>;
212 fn default_message_from_id(id: u32) -> Option<Self>;
214 #[cfg(feature = "arbitrary")]
216 fn random_message_from_id<R: rand::RngCore>(id: u32, rng: &mut R) -> Option<Self>;
217 fn extra_crc(id: u32) -> u8;
219}
220
221pub trait MessageData: Sized {
222 type Message: Message;
223
224 const ID: u32;
225 const NAME: &'static str;
226 const EXTRA_CRC: u8;
227 const ENCODED_LEN: usize;
228
229 fn ser(&self, version: MavlinkVersion, payload: &mut [u8]) -> usize;
233 fn deser(version: MavlinkVersion, payload: &[u8]) -> Result<Self, ParserError>;
237}
238
239#[derive(Debug, Copy, Clone, PartialEq, Eq)]
241#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
242#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
243pub struct MavHeader {
244 pub system_id: u8,
246 pub component_id: u8,
248 pub sequence: u8,
250}
251
252#[derive(Debug, Copy, Clone, PartialEq, Eq)]
254#[cfg_attr(feature = "serde", derive(Serialize))]
255#[cfg_attr(feature = "serde", serde(tag = "type"))]
256#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
257pub enum MavlinkVersion {
258 V1,
260 V2,
262}
263
264pub const MAV_STX: u8 = 0xFE;
266
267pub const MAV_STX_V2: u8 = 0xFD;
269
270impl Default for MavHeader {
273 fn default() -> Self {
274 Self {
275 system_id: 255,
276 component_id: 0,
277 sequence: 0,
278 }
279 }
280}
281
282#[derive(Debug, Clone)]
286#[cfg_attr(feature = "serde", derive(Serialize))]
287#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
288pub struct MavFrame<M: Message> {
289 pub header: MavHeader,
291 pub msg: M,
293 pub protocol_version: MavlinkVersion,
295}
296
297impl<M: Message> MavFrame<M> {
298 pub fn ser(&self, buf: &mut [u8]) -> usize {
307 let mut buf = bytes_mut::BytesMut::new(buf);
308
309 let mut payload_buf = [0u8; 255];
311 let payload_len = self.msg.ser(self.protocol_version, &mut payload_buf);
312
313 buf.put_u8(self.header.sequence);
332 buf.put_u8(self.header.system_id);
333 buf.put_u8(self.header.component_id);
334
335 match self.protocol_version {
337 MavlinkVersion::V2 => {
338 let bytes: [u8; 4] = self.msg.message_id().to_le_bytes();
339 buf.put_slice(&bytes[..3]);
340 }
341 MavlinkVersion::V1 => {
342 buf.put_u8(
343 self.msg
344 .message_id()
345 .try_into()
346 .expect("message is MAVLink 2 only"),
347 );
348 }
349 }
350
351 buf.put_slice(&payload_buf[..payload_len]);
352 buf.len()
353 }
354
355 pub fn deser(version: MavlinkVersion, input: &[u8]) -> Result<Self, ParserError> {
364 let mut buf = Bytes::new(input);
365
366 let sequence = buf.get_u8()?;
376 let system_id = buf.get_u8()?;
377 let component_id = buf.get_u8()?;
378 let header = MavHeader {
379 system_id,
380 component_id,
381 sequence,
382 };
383
384 let msg_id = match version {
385 MavlinkVersion::V2 => buf.get_u24_le()?,
386 MavlinkVersion::V1 => buf.get_u8()?.into(),
387 };
388
389 M::parse(version, msg_id, buf.remaining_bytes()).map(|msg| Self {
390 header,
391 msg,
392 protocol_version: version,
393 })
394 }
395
396 pub fn header(&self) -> MavHeader {
398 self.header
399 }
400}
401
402pub fn calculate_crc(data: &[u8], extra_crc: u8) -> u16 {
404 let mut crc_calculator = CRCu16::crc16mcrf4cc();
405 crc_calculator.digest(data);
406
407 crc_calculator.digest(&[extra_crc]);
408 crc_calculator.get_crc()
409}
410
411#[derive(Debug, Clone, Copy, PartialEq, Eq)]
412pub enum ReadVersion {
414 Single(MavlinkVersion),
416 Any,
418}
419
420impl From<MavlinkVersion> for ReadVersion {
421 fn from(value: MavlinkVersion) -> Self {
422 Self::Single(value)
423 }
424}
425
426pub fn read_versioned_msg<M: Message, R: Read>(
432 r: &mut PeekReader<R>,
433 version: ReadVersion,
434) -> Result<(MavHeader, M), MessageReadError> {
435 match version {
436 ReadVersion::Single(MavlinkVersion::V2) => read_v2_msg(r),
437 ReadVersion::Single(MavlinkVersion::V1) => read_v1_msg(r),
438 ReadVersion::Any => read_any_msg(r),
439 }
440}
441
442pub fn read_versioned_raw_message<M: Message, R: Read>(
448 r: &mut PeekReader<R>,
449 version: ReadVersion,
450) -> Result<MAVLinkMessageRaw, MessageReadError> {
451 match version {
452 ReadVersion::Single(MavlinkVersion::V2) => {
453 Ok(MAVLinkMessageRaw::V2(read_v2_raw_message::<M, _>(r)?))
454 }
455 ReadVersion::Single(MavlinkVersion::V1) => {
456 Ok(MAVLinkMessageRaw::V1(read_v1_raw_message::<M, _>(r)?))
457 }
458 ReadVersion::Any => read_any_raw_message::<M, _>(r),
459 }
460}
461
462#[cfg(feature = "tokio")]
468pub async fn read_versioned_msg_async<M: Message, R: tokio::io::AsyncRead + Unpin>(
469 r: &mut AsyncPeekReader<R>,
470 version: ReadVersion,
471) -> Result<(MavHeader, M), MessageReadError> {
472 match version {
473 ReadVersion::Single(MavlinkVersion::V2) => read_v2_msg_async(r).await,
474 ReadVersion::Single(MavlinkVersion::V1) => read_v1_msg_async(r).await,
475 ReadVersion::Any => read_any_msg_async(r).await,
476 }
477}
478
479#[cfg(feature = "tokio")]
485pub async fn read_versioned_raw_message_async<M: Message, R: tokio::io::AsyncRead + Unpin>(
486 r: &mut AsyncPeekReader<R>,
487 version: ReadVersion,
488) -> Result<MAVLinkMessageRaw, MessageReadError> {
489 match version {
490 ReadVersion::Single(MavlinkVersion::V2) => Ok(MAVLinkMessageRaw::V2(
491 read_v2_raw_message_async::<M, _>(r).await?,
492 )),
493 ReadVersion::Single(MavlinkVersion::V1) => Ok(MAVLinkMessageRaw::V1(
494 read_v1_raw_message_async::<M, _>(r).await?,
495 )),
496 ReadVersion::Any => read_any_raw_message_async::<M, _>(r).await,
497 }
498}
499
500#[cfg(feature = "mav2-message-signing")]
509pub fn read_versioned_raw_message_signed<M: Message, R: Read>(
510 r: &mut PeekReader<R>,
511 version: ReadVersion,
512 signing_data: Option<&SigningData>,
513) -> Result<MAVLinkMessageRaw, MessageReadError> {
514 match version {
515 ReadVersion::Single(MavlinkVersion::V2) => Ok(MAVLinkMessageRaw::V2(
516 read_v2_raw_message_inner::<M, _>(r, signing_data)?,
517 )),
518 ReadVersion::Single(MavlinkVersion::V1) => {
519 Ok(MAVLinkMessageRaw::V1(read_v1_raw_message::<M, _>(r)?))
520 }
521 ReadVersion::Any => read_any_raw_message_inner::<M, _>(r, signing_data),
522 }
523}
524
525#[cfg(feature = "mav2-message-signing")]
534pub fn read_versioned_msg_signed<M: Message, R: Read>(
535 r: &mut PeekReader<R>,
536 version: ReadVersion,
537 signing_data: Option<&SigningData>,
538) -> Result<(MavHeader, M), MessageReadError> {
539 match version {
540 ReadVersion::Single(MavlinkVersion::V2) => read_v2_msg_inner(r, signing_data),
541 ReadVersion::Single(MavlinkVersion::V1) => read_v1_msg(r),
542 ReadVersion::Any => read_any_msg_inner(r, signing_data),
543 }
544}
545
546#[cfg(all(feature = "tokio", feature = "mav2-message-signing"))]
555pub async fn read_versioned_raw_message_async_signed<
556 M: Message,
557 R: tokio::io::AsyncRead + Unpin,
558>(
559 r: &mut AsyncPeekReader<R>,
560 version: ReadVersion,
561 signing_data: Option<&SigningData>,
562) -> Result<MAVLinkMessageRaw, MessageReadError> {
563 match version {
564 ReadVersion::Single(MavlinkVersion::V2) => Ok(MAVLinkMessageRaw::V2(
565 read_v2_raw_message_async_inner::<M, _>(r, signing_data).await?,
566 )),
567 ReadVersion::Single(MavlinkVersion::V1) => Ok(MAVLinkMessageRaw::V1(
568 read_v1_raw_message_async::<M, _>(r).await?,
569 )),
570 ReadVersion::Any => read_any_raw_message_async_inner::<M, _>(r, signing_data).await,
571 }
572}
573
574#[cfg(all(feature = "tokio", feature = "mav2-message-signing"))]
583pub async fn read_versioned_msg_async_signed<M: Message, R: tokio::io::AsyncRead + Unpin>(
584 r: &mut AsyncPeekReader<R>,
585 version: ReadVersion,
586 signing_data: Option<&SigningData>,
587) -> Result<(MavHeader, M), MessageReadError> {
588 match version {
589 ReadVersion::Single(MavlinkVersion::V2) => read_v2_msg_async_inner(r, signing_data).await,
590 ReadVersion::Single(MavlinkVersion::V1) => read_v1_msg_async(r).await,
591 ReadVersion::Any => read_any_msg_async_inner(r, signing_data).await,
592 }
593}
594
595#[derive(Debug, Copy, Clone, PartialEq, Eq)]
596pub struct MAVLinkV1MessageRaw([u8; 1 + Self::HEADER_SIZE + 255 + 2]);
601
602impl Default for MAVLinkV1MessageRaw {
603 fn default() -> Self {
604 Self::new()
605 }
606}
607
608impl MAVLinkV1MessageRaw {
609 const HEADER_SIZE: usize = 5;
610
611 pub const fn new() -> Self {
613 Self([0; 1 + Self::HEADER_SIZE + 255 + 2])
614 }
615
616 pub const fn from_bytes_unparsed(bytes: [u8; 1 + Self::HEADER_SIZE + 255 + 2]) -> Self {
620 Self(bytes)
621 }
622
623 #[inline]
625 pub fn as_slice(&self) -> &[u8] {
626 &self.0
627 }
628
629 #[inline]
631 pub fn as_mut_slice(&mut self) -> &mut [u8] {
632 &mut self.0
633 }
634
635 #[inline]
637 pub fn into_inner(self) -> [u8; 1 + Self::HEADER_SIZE + 255 + 2] {
638 self.0
639 }
640
641 #[inline]
643 pub fn header(&self) -> &[u8] {
644 &self.0[1..=Self::HEADER_SIZE]
645 }
646
647 #[inline]
649 fn mut_header(&mut self) -> &mut [u8] {
650 &mut self.0[1..=Self::HEADER_SIZE]
651 }
652
653 #[inline]
655 pub fn payload_length(&self) -> u8 {
656 self.0[1]
657 }
658
659 #[inline]
661 pub fn sequence(&self) -> u8 {
662 self.0[2]
663 }
664
665 #[inline]
667 pub fn system_id(&self) -> u8 {
668 self.0[3]
669 }
670
671 #[inline]
673 pub fn component_id(&self) -> u8 {
674 self.0[4]
675 }
676
677 #[inline]
679 pub fn message_id(&self) -> u8 {
680 self.0[5]
681 }
682
683 #[inline]
685 pub fn payload(&self) -> &[u8] {
686 let payload_length: usize = self.payload_length().into();
687 &self.0[(1 + Self::HEADER_SIZE)..(1 + Self::HEADER_SIZE + payload_length)]
688 }
689
690 #[inline]
692 pub fn checksum(&self) -> u16 {
693 let payload_length: usize = self.payload_length().into();
694 u16::from_le_bytes([
695 self.0[1 + Self::HEADER_SIZE + payload_length],
696 self.0[1 + Self::HEADER_SIZE + payload_length + 1],
697 ])
698 }
699
700 #[inline]
701 fn mut_payload_and_checksum(&mut self) -> &mut [u8] {
702 let payload_length: usize = self.payload_length().into();
703 &mut self.0[(1 + Self::HEADER_SIZE)..(1 + Self::HEADER_SIZE + payload_length + 2)]
704 }
705
706 #[inline]
708 pub fn has_valid_crc<M: Message>(&self) -> bool {
709 let payload_length: usize = self.payload_length().into();
710 self.checksum()
711 == calculate_crc(
712 &self.0[1..(1 + Self::HEADER_SIZE + payload_length)],
713 M::extra_crc(self.message_id().into()),
714 )
715 }
716
717 pub fn raw_bytes(&self) -> &[u8] {
719 let payload_length = self.payload_length() as usize;
720 &self.0[..(1 + Self::HEADER_SIZE + payload_length + 2)]
721 }
722
723 fn serialize_stx_and_header_and_crc(
727 &mut self,
728 header: MavHeader,
729 msgid: u32,
730 payload_length: usize,
731 extra_crc: u8,
732 ) {
733 self.0[0] = MAV_STX;
734
735 let header_buf = self.mut_header();
736 header_buf.copy_from_slice(&[
737 payload_length as u8,
738 header.sequence,
739 header.system_id,
740 header.component_id,
741 msgid.try_into().unwrap(),
742 ]);
743
744 let crc = calculate_crc(
745 &self.0[1..(1 + Self::HEADER_SIZE + payload_length)],
746 extra_crc,
747 );
748 self.0[(1 + Self::HEADER_SIZE + payload_length)
749 ..(1 + Self::HEADER_SIZE + payload_length + 2)]
750 .copy_from_slice(&crc.to_le_bytes());
751 }
752
753 pub fn serialize_message<M: Message>(&mut self, header: MavHeader, message: &M) {
759 let payload_buf = &mut self.0[(1 + Self::HEADER_SIZE)..(1 + Self::HEADER_SIZE + 255)];
760 let payload_length = message.ser(MavlinkVersion::V1, payload_buf);
761
762 let message_id = message.message_id();
763 self.serialize_stx_and_header_and_crc(
764 header,
765 message_id,
766 payload_length,
767 M::extra_crc(message_id),
768 );
769 }
770
771 pub fn serialize_message_data<D: MessageData>(&mut self, header: MavHeader, message_data: &D) {
775 let payload_buf = &mut self.0[(1 + Self::HEADER_SIZE)..(1 + Self::HEADER_SIZE + 255)];
776 let payload_length = message_data.ser(MavlinkVersion::V1, payload_buf);
777
778 self.serialize_stx_and_header_and_crc(header, D::ID, payload_length, D::EXTRA_CRC);
779 }
780}
781
782fn try_decode_v1<M: Message, R: Read>(
783 reader: &mut PeekReader<R>,
784) -> Result<Option<MAVLinkV1MessageRaw>, MessageReadError> {
785 let mut message = MAVLinkV1MessageRaw::new();
786 let whole_header_size = MAVLinkV1MessageRaw::HEADER_SIZE + 1;
787
788 message.0[0] = MAV_STX;
789 let header = &reader.peek_exact(whole_header_size)?[1..whole_header_size];
790 message.mut_header().copy_from_slice(header);
791 let packet_length = message.raw_bytes().len();
792 let payload_and_checksum = &reader.peek_exact(packet_length)?[whole_header_size..packet_length];
793 message
794 .mut_payload_and_checksum()
795 .copy_from_slice(payload_and_checksum);
796
797 if message.has_valid_crc::<M>() {
800 reader.consume(message.raw_bytes().len());
801 Ok(Some(message))
802 } else {
803 Ok(None)
804 }
805}
806
807#[cfg(feature = "tokio")]
808async fn try_decode_v1_async<M: Message, R: tokio::io::AsyncRead + Unpin>(
810 reader: &mut AsyncPeekReader<R>,
811) -> Result<Option<MAVLinkV1MessageRaw>, MessageReadError> {
812 let mut message = MAVLinkV1MessageRaw::new();
813
814 message.0[0] = MAV_STX;
815 let header = &reader.peek_exact(MAVLinkV1MessageRaw::HEADER_SIZE).await?
816 [..MAVLinkV1MessageRaw::HEADER_SIZE];
817 message.mut_header().copy_from_slice(header);
818 let packet_length = message.raw_bytes().len() - 1;
819 let payload_and_checksum =
820 &reader.peek_exact(packet_length).await?[MAVLinkV1MessageRaw::HEADER_SIZE..packet_length];
821 message
822 .mut_payload_and_checksum()
823 .copy_from_slice(payload_and_checksum);
824
825 if message.has_valid_crc::<M>() {
828 reader.consume(message.raw_bytes().len() - 1);
829 Ok(Some(message))
830 } else {
831 Ok(None)
832 }
833}
834
835pub fn read_v1_raw_message<M: Message, R: Read>(
841 reader: &mut PeekReader<R>,
842) -> Result<MAVLinkV1MessageRaw, MessageReadError> {
843 loop {
844 while reader.peek_exact(1)?[0] != MAV_STX {
846 reader.consume(1);
847 }
848
849 if let Some(msg) = try_decode_v1::<M, _>(reader)? {
850 return Ok(msg);
851 }
852
853 reader.consume(1);
854 }
855}
856
857#[cfg(feature = "tokio")]
863pub async fn read_v1_raw_message_async<M: Message, R: tokio::io::AsyncRead + Unpin>(
864 reader: &mut AsyncPeekReader<R>,
865) -> Result<MAVLinkV1MessageRaw, MessageReadError> {
866 loop {
867 loop {
868 if reader.read_u8().await? == MAV_STX {
870 break;
871 }
872 }
873
874 if let Some(message) = try_decode_v1_async::<M, _>(reader).await? {
875 return Ok(message);
876 }
877 }
878}
879
880#[cfg(all(feature = "embedded", not(feature = "std")))]
887pub async fn read_v1_raw_message_async<M: Message>(
888 reader: &mut impl embedded_io_async::Read,
889) -> Result<MAVLinkV1MessageRaw, MessageReadError> {
890 loop {
891 let mut byte = [0u8];
893 loop {
894 reader
895 .read_exact(&mut byte)
896 .await
897 .map_err(|_| MessageReadError::Io)?;
898 if byte[0] == MAV_STX {
899 break;
900 }
901 }
902
903 let mut message = MAVLinkV1MessageRaw::new();
904
905 message.0[0] = MAV_STX;
906 reader
907 .read_exact(message.mut_header())
908 .await
909 .map_err(|_| MessageReadError::Io)?;
910 reader
911 .read_exact(message.mut_payload_and_checksum())
912 .await
913 .map_err(|_| MessageReadError::Io)?;
914
915 if message.has_valid_crc::<M>() {
918 return Ok(message);
919 }
920 }
921}
922
923pub fn read_v1_msg<M: Message, R: Read>(
929 r: &mut PeekReader<R>,
930) -> Result<(MavHeader, M), MessageReadError> {
931 let message = read_v1_raw_message::<M, _>(r)?;
932
933 Ok((
934 MavHeader {
935 sequence: message.sequence(),
936 system_id: message.system_id(),
937 component_id: message.component_id(),
938 },
939 M::parse(
940 MavlinkVersion::V1,
941 u32::from(message.message_id()),
942 message.payload(),
943 )?,
944 ))
945}
946
947#[cfg(feature = "tokio")]
953pub async fn read_v1_msg_async<M: Message, R: tokio::io::AsyncRead + Unpin>(
954 r: &mut AsyncPeekReader<R>,
955) -> Result<(MavHeader, M), MessageReadError> {
956 let message = read_v1_raw_message_async::<M, _>(r).await?;
957
958 Ok((
959 MavHeader {
960 sequence: message.sequence(),
961 system_id: message.system_id(),
962 component_id: message.component_id(),
963 },
964 M::parse(
965 MavlinkVersion::V1,
966 u32::from(message.message_id()),
967 message.payload(),
968 )?,
969 ))
970}
971
972#[cfg(all(feature = "embedded", not(feature = "std")))]
977pub async fn read_v1_msg_async<M: Message>(
978 r: &mut impl embedded_io_async::Read,
979) -> Result<(MavHeader, M), MessageReadError> {
980 let message = read_v1_raw_message_async::<M>(r).await?;
981
982 Ok((
983 MavHeader {
984 sequence: message.sequence(),
985 system_id: message.system_id(),
986 component_id: message.component_id(),
987 },
988 M::parse(
989 MavlinkVersion::V1,
990 u32::from(message.message_id()),
991 message.payload(),
992 )?,
993 ))
994}
995
996const MAVLINK_IFLAG_SIGNED: u8 = 0x01;
997const MAVLINK_SUPPORTED_IFLAGS: u8 = MAVLINK_IFLAG_SIGNED;
998
999#[derive(Debug, Copy, Clone, PartialEq, Eq)]
1000pub struct MAVLinkV2MessageRaw([u8; 1 + Self::HEADER_SIZE + 255 + 2 + Self::SIGNATURE_SIZE]);
1005
1006impl Default for MAVLinkV2MessageRaw {
1007 fn default() -> Self {
1008 Self::new()
1009 }
1010}
1011
1012impl MAVLinkV2MessageRaw {
1013 const HEADER_SIZE: usize = 9;
1014 const SIGNATURE_SIZE: usize = 13;
1015
1016 pub const fn new() -> Self {
1018 Self([0; 1 + Self::HEADER_SIZE + 255 + 2 + Self::SIGNATURE_SIZE])
1019 }
1020
1021 pub const fn from_bytes_unparsed(
1025 bytes: [u8; 1 + Self::HEADER_SIZE + 255 + 2 + Self::SIGNATURE_SIZE],
1026 ) -> Self {
1027 Self(bytes)
1028 }
1029
1030 #[inline]
1032 pub fn as_slice(&self) -> &[u8] {
1033 &self.0
1034 }
1035
1036 #[inline]
1038 pub fn as_mut_slice(&mut self) -> &mut [u8] {
1039 &mut self.0
1040 }
1041
1042 #[inline]
1044 pub fn into_inner(self) -> [u8; 1 + Self::HEADER_SIZE + 255 + 2 + Self::SIGNATURE_SIZE] {
1045 self.0
1046 }
1047
1048 #[inline]
1050 pub fn header(&self) -> &[u8] {
1051 &self.0[1..=Self::HEADER_SIZE]
1052 }
1053
1054 #[inline]
1056 fn mut_header(&mut self) -> &mut [u8] {
1057 &mut self.0[1..=Self::HEADER_SIZE]
1058 }
1059
1060 #[inline]
1062 pub fn payload_length(&self) -> u8 {
1063 self.0[1]
1064 }
1065
1066 #[inline]
1070 pub fn incompatibility_flags(&self) -> u8 {
1071 self.0[2]
1072 }
1073
1074 #[inline]
1078 pub fn incompatibility_flags_mut(&mut self) -> &mut u8 {
1079 &mut self.0[2]
1080 }
1081
1082 #[inline]
1084 pub fn compatibility_flags(&self) -> u8 {
1085 self.0[3]
1086 }
1087
1088 #[inline]
1090 pub fn sequence(&self) -> u8 {
1091 self.0[4]
1092 }
1093
1094 #[inline]
1096 pub fn system_id(&self) -> u8 {
1097 self.0[5]
1098 }
1099
1100 #[inline]
1102 pub fn component_id(&self) -> u8 {
1103 self.0[6]
1104 }
1105
1106 #[inline]
1108 pub fn message_id(&self) -> u32 {
1109 u32::from_le_bytes([self.0[7], self.0[8], self.0[9], 0])
1110 }
1111
1112 #[inline]
1114 pub fn payload(&self) -> &[u8] {
1115 let payload_length: usize = self.payload_length().into();
1116 &self.0[(1 + Self::HEADER_SIZE)..(1 + Self::HEADER_SIZE + payload_length)]
1117 }
1118
1119 #[inline]
1121 pub fn checksum(&self) -> u16 {
1122 let payload_length: usize = self.payload_length().into();
1123 u16::from_le_bytes([
1124 self.0[1 + Self::HEADER_SIZE + payload_length],
1125 self.0[1 + Self::HEADER_SIZE + payload_length + 1],
1126 ])
1127 }
1128
1129 #[cfg(feature = "mav2-message-signing")]
1131 #[inline]
1132 pub fn checksum_bytes(&self) -> &[u8] {
1133 let checksum_offset = 1 + Self::HEADER_SIZE + self.payload_length() as usize;
1134 &self.0[checksum_offset..(checksum_offset + 2)]
1135 }
1136
1137 #[cfg(feature = "mav2-message-signing")]
1141 #[inline]
1142 pub fn signature_link_id(&self) -> u8 {
1143 let payload_length: usize = self.payload_length().into();
1144 self.0[1 + Self::HEADER_SIZE + payload_length + 2]
1145 }
1146
1147 #[cfg(feature = "mav2-message-signing")]
1149 #[inline]
1150 pub fn signature_link_id_mut(&mut self) -> &mut u8 {
1151 let payload_length: usize = self.payload_length().into();
1152 &mut self.0[1 + Self::HEADER_SIZE + payload_length + 2]
1153 }
1154
1155 #[cfg(feature = "mav2-message-signing")]
1161 #[inline]
1162 pub fn signature_timestamp(&self) -> u64 {
1163 let mut timestamp_bytes = [0u8; 8];
1164 timestamp_bytes[0..6].copy_from_slice(self.signature_timestamp_bytes());
1165 u64::from_le_bytes(timestamp_bytes)
1166 }
1167
1168 #[cfg(feature = "mav2-message-signing")]
1172 #[inline]
1173 pub fn signature_timestamp_bytes(&self) -> &[u8] {
1174 let payload_length: usize = self.payload_length().into();
1175 let timestamp_start = 1 + Self::HEADER_SIZE + payload_length + 3;
1176 &self.0[timestamp_start..(timestamp_start + 6)]
1177 }
1178
1179 #[cfg(feature = "mav2-message-signing")]
1181 #[inline]
1182 pub fn signature_timestamp_bytes_mut(&mut self) -> &mut [u8] {
1183 let payload_length: usize = self.payload_length().into();
1184 let timestamp_start = 1 + Self::HEADER_SIZE + payload_length + 3;
1185 &mut self.0[timestamp_start..(timestamp_start + 6)]
1186 }
1187
1188 #[cfg(feature = "mav2-message-signing")]
1192 #[inline]
1193 pub fn signature_value(&self) -> &[u8] {
1194 let payload_length: usize = self.payload_length().into();
1195 let signature_start = 1 + Self::HEADER_SIZE + payload_length + 3 + 6;
1196 &self.0[signature_start..(signature_start + 6)]
1197 }
1198
1199 #[cfg(feature = "mav2-message-signing")]
1201 #[inline]
1202 pub fn signature_value_mut(&mut self) -> &mut [u8] {
1203 let payload_length: usize = self.payload_length().into();
1204 let signature_start = 1 + Self::HEADER_SIZE + payload_length + 3 + 6;
1205 &mut self.0[signature_start..(signature_start + 6)]
1206 }
1207
1208 fn mut_payload_and_checksum_and_sign(&mut self) -> &mut [u8] {
1209 let payload_length: usize = self.payload_length().into();
1210
1211 let signature_size = if (self.incompatibility_flags() & MAVLINK_IFLAG_SIGNED) == 0 {
1213 0
1214 } else {
1215 Self::SIGNATURE_SIZE
1216 };
1217
1218 &mut self.0
1219 [(1 + Self::HEADER_SIZE)..(1 + Self::HEADER_SIZE + payload_length + signature_size + 2)]
1220 }
1221
1222 #[inline]
1224 pub fn has_valid_crc<M: Message>(&self) -> bool {
1225 let payload_length: usize = self.payload_length().into();
1226 self.checksum()
1227 == calculate_crc(
1228 &self.0[1..(1 + Self::HEADER_SIZE + payload_length)],
1229 M::extra_crc(self.message_id()),
1230 )
1231 }
1232
1233 #[cfg(feature = "mav2-message-signing")]
1237 pub fn calculate_signature(&self, secret_key: &[u8], target_buffer: &mut [u8; 6]) {
1238 let mut hasher = Sha256::new();
1239 hasher.update(secret_key);
1240 hasher.update([MAV_STX_V2]);
1241 hasher.update(self.header());
1242 hasher.update(self.payload());
1243 hasher.update(self.checksum_bytes());
1244 hasher.update([self.signature_link_id()]);
1245 hasher.update(self.signature_timestamp_bytes());
1246 target_buffer.copy_from_slice(&hasher.finalize()[0..6]);
1247 }
1248
1249 pub fn raw_bytes(&self) -> &[u8] {
1251 let payload_length = self.payload_length() as usize;
1252
1253 let signature_size = if (self.incompatibility_flags() & MAVLINK_IFLAG_SIGNED) == 0 {
1254 0
1255 } else {
1256 Self::SIGNATURE_SIZE
1257 };
1258
1259 &self.0[..(1 + Self::HEADER_SIZE + payload_length + signature_size + 2)]
1260 }
1261
1262 fn serialize_stx_and_header_and_crc(
1263 &mut self,
1264 header: MavHeader,
1265 msgid: u32,
1266 payload_length: usize,
1267 extra_crc: u8,
1268 incompat_flags: u8,
1269 ) {
1270 self.0[0] = MAV_STX_V2;
1271 let msgid_bytes = msgid.to_le_bytes();
1272
1273 let header_buf = self.mut_header();
1274 header_buf.copy_from_slice(&[
1275 payload_length as u8,
1276 incompat_flags,
1277 0, header.sequence,
1279 header.system_id,
1280 header.component_id,
1281 msgid_bytes[0],
1282 msgid_bytes[1],
1283 msgid_bytes[2],
1284 ]);
1285
1286 let crc = calculate_crc(
1287 &self.0[1..(1 + Self::HEADER_SIZE + payload_length)],
1288 extra_crc,
1289 );
1290 self.0[(1 + Self::HEADER_SIZE + payload_length)
1291 ..(1 + Self::HEADER_SIZE + payload_length + 2)]
1292 .copy_from_slice(&crc.to_le_bytes());
1293 }
1294
1295 pub fn serialize_message<M: Message>(&mut self, header: MavHeader, message: &M) {
1299 let payload_buf = &mut self.0[(1 + Self::HEADER_SIZE)..(1 + Self::HEADER_SIZE + 255)];
1300 let payload_length = message.ser(MavlinkVersion::V2, payload_buf);
1301
1302 let message_id = message.message_id();
1303 self.serialize_stx_and_header_and_crc(
1304 header,
1305 message_id,
1306 payload_length,
1307 M::extra_crc(message_id),
1308 0,
1309 );
1310 }
1311
1312 pub fn serialize_message_for_signing<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 MAVLINK_IFLAG_SIGNED,
1327 );
1328 }
1329
1330 pub fn serialize_message_data<D: MessageData>(&mut self, header: MavHeader, message_data: &D) {
1331 let payload_buf = &mut self.0[(1 + Self::HEADER_SIZE)..(1 + Self::HEADER_SIZE + 255)];
1332 let payload_length = message_data.ser(MavlinkVersion::V2, payload_buf);
1333
1334 self.serialize_stx_and_header_and_crc(header, D::ID, payload_length, D::EXTRA_CRC, 0);
1335 }
1336}
1337
1338#[allow(unused_variables)]
1339fn try_decode_v2<M: Message, R: Read>(
1340 reader: &mut PeekReader<R>,
1341 signing_data: Option<&SigningData>,
1342) -> Result<Option<MAVLinkV2MessageRaw>, MessageReadError> {
1343 let mut message = MAVLinkV2MessageRaw::new();
1344 let whole_header_size = MAVLinkV2MessageRaw::HEADER_SIZE + 1;
1345
1346 message.0[0] = MAV_STX_V2;
1347 let header = &reader.peek_exact(whole_header_size)?[1..whole_header_size];
1348 message.mut_header().copy_from_slice(header);
1349
1350 if message.incompatibility_flags() & !MAVLINK_SUPPORTED_IFLAGS > 0 {
1351 reader.consume(1);
1353 return Ok(None);
1354 }
1355
1356 let packet_length = message.raw_bytes().len();
1357 let payload_and_checksum_and_sign =
1358 &reader.peek_exact(packet_length)?[whole_header_size..packet_length];
1359 message
1360 .mut_payload_and_checksum_and_sign()
1361 .copy_from_slice(payload_and_checksum_and_sign);
1362
1363 if message.has_valid_crc::<M>() {
1364 reader.consume(message.raw_bytes().len());
1366 } else {
1367 reader.consume(1);
1368 return Ok(None);
1369 }
1370
1371 #[cfg(feature = "mav2-message-signing")]
1372 if let Some(signing_data) = signing_data {
1373 if !signing_data.verify_signature(&message) {
1374 return Ok(None);
1375 }
1376 }
1377
1378 Ok(Some(message))
1379}
1380
1381#[cfg(feature = "tokio")]
1382#[allow(unused_variables)]
1383async fn try_decode_v2_async<M: Message, R: tokio::io::AsyncRead + Unpin>(
1385 reader: &mut AsyncPeekReader<R>,
1386 signing_data: Option<&SigningData>,
1387) -> Result<Option<MAVLinkV2MessageRaw>, MessageReadError> {
1388 let mut message = MAVLinkV2MessageRaw::new();
1389
1390 message.0[0] = MAV_STX_V2;
1391 let header = &reader.peek_exact(MAVLinkV2MessageRaw::HEADER_SIZE).await?
1392 [..MAVLinkV2MessageRaw::HEADER_SIZE];
1393 message.mut_header().copy_from_slice(header);
1394
1395 if message.incompatibility_flags() & !MAVLINK_SUPPORTED_IFLAGS > 0 {
1396 return Ok(None);
1398 }
1399
1400 let packet_length = message.raw_bytes().len() - 1;
1401 let payload_and_checksum_and_sign =
1402 &reader.peek_exact(packet_length).await?[MAVLinkV2MessageRaw::HEADER_SIZE..packet_length];
1403 message
1404 .mut_payload_and_checksum_and_sign()
1405 .copy_from_slice(payload_and_checksum_and_sign);
1406
1407 if message.has_valid_crc::<M>() {
1408 reader.consume(message.raw_bytes().len() - 1);
1410 } else {
1411 return Ok(None);
1412 }
1413
1414 #[cfg(feature = "mav2-message-signing")]
1415 if let Some(signing_data) = signing_data {
1416 if !signing_data.verify_signature(&message) {
1417 return Ok(None);
1418 }
1419 }
1420
1421 Ok(Some(message))
1422}
1423
1424#[inline]
1430pub fn read_v2_raw_message<M: Message, R: Read>(
1431 reader: &mut PeekReader<R>,
1432) -> Result<MAVLinkV2MessageRaw, MessageReadError> {
1433 read_v2_raw_message_inner::<M, R>(reader, None)
1434}
1435
1436#[cfg(feature = "mav2-message-signing")]
1442#[inline]
1443pub fn read_v2_raw_message_signed<M: Message, R: Read>(
1444 reader: &mut PeekReader<R>,
1445 signing_data: Option<&SigningData>,
1446) -> Result<MAVLinkV2MessageRaw, MessageReadError> {
1447 read_v2_raw_message_inner::<M, R>(reader, signing_data)
1448}
1449
1450#[allow(unused_variables)]
1451fn read_v2_raw_message_inner<M: Message, R: Read>(
1452 reader: &mut PeekReader<R>,
1453 signing_data: Option<&SigningData>,
1454) -> Result<MAVLinkV2MessageRaw, MessageReadError> {
1455 loop {
1456 while reader.peek_exact(1)?[0] != MAV_STX_V2 {
1458 reader.consume(1);
1459 }
1460
1461 if let Some(message) = try_decode_v2::<M, _>(reader, signing_data)? {
1462 return Ok(message);
1463 }
1464 }
1465}
1466
1467#[cfg(feature = "tokio")]
1473pub async fn read_v2_raw_message_async<M: Message, R: tokio::io::AsyncRead + Unpin>(
1474 reader: &mut AsyncPeekReader<R>,
1475) -> Result<MAVLinkV2MessageRaw, MessageReadError> {
1476 read_v2_raw_message_async_inner::<M, R>(reader, None).await
1477}
1478
1479#[cfg(feature = "tokio")]
1480#[allow(unused_variables)]
1481async fn read_v2_raw_message_async_inner<M: Message, R: tokio::io::AsyncRead + Unpin>(
1482 reader: &mut AsyncPeekReader<R>,
1483 signing_data: Option<&SigningData>,
1484) -> Result<MAVLinkV2MessageRaw, MessageReadError> {
1485 loop {
1486 loop {
1487 if reader.read_u8().await? == MAV_STX_V2 {
1489 break;
1490 }
1491 }
1492
1493 if let Some(message) = try_decode_v2_async::<M, _>(reader, signing_data).await? {
1494 return Ok(message);
1495 }
1496 }
1497}
1498
1499#[cfg(all(feature = "tokio", feature = "mav2-message-signing"))]
1505pub async fn read_v2_raw_message_async_signed<M: Message, R: tokio::io::AsyncRead + Unpin>(
1506 reader: &mut AsyncPeekReader<R>,
1507 signing_data: Option<&SigningData>,
1508) -> Result<MAVLinkV2MessageRaw, MessageReadError> {
1509 read_v2_raw_message_async_inner::<M, R>(reader, signing_data).await
1510}
1511
1512#[cfg(all(feature = "embedded", not(feature = "std")))]
1518pub async fn read_v2_raw_message_async<M: Message>(
1519 reader: &mut impl embedded_io_async::Read,
1520) -> Result<MAVLinkV2MessageRaw, MessageReadError> {
1521 loop {
1522 let mut byte = [0u8];
1524 loop {
1525 reader
1526 .read_exact(&mut byte)
1527 .await
1528 .map_err(|_| MessageReadError::Io)?;
1529 if byte[0] == MAV_STX_V2 {
1530 break;
1531 }
1532 }
1533
1534 let mut message = MAVLinkV2MessageRaw::new();
1535
1536 message.0[0] = MAV_STX_V2;
1537 reader
1538 .read_exact(message.mut_header())
1539 .await
1540 .map_err(|_| MessageReadError::Io)?;
1541
1542 if message.incompatibility_flags() & !MAVLINK_SUPPORTED_IFLAGS > 0 {
1543 continue;
1545 }
1546
1547 reader
1548 .read_exact(message.mut_payload_and_checksum_and_sign())
1549 .await
1550 .map_err(|_| MessageReadError::Io)?;
1551
1552 if message.has_valid_crc::<M>() {
1555 return Ok(message);
1556 }
1557 }
1558}
1559
1560#[inline]
1566pub fn read_v2_msg<M: Message, R: Read>(
1567 read: &mut PeekReader<R>,
1568) -> Result<(MavHeader, M), MessageReadError> {
1569 read_v2_msg_inner(read, None)
1570}
1571
1572#[cfg(feature = "mav2-message-signing")]
1578#[inline]
1579pub fn read_v2_msg_signed<M: Message, R: Read>(
1580 read: &mut PeekReader<R>,
1581 signing_data: Option<&SigningData>,
1582) -> Result<(MavHeader, M), MessageReadError> {
1583 read_v2_msg_inner(read, signing_data)
1584}
1585
1586fn read_v2_msg_inner<M: Message, R: Read>(
1587 read: &mut PeekReader<R>,
1588 signing_data: Option<&SigningData>,
1589) -> Result<(MavHeader, M), MessageReadError> {
1590 let message = read_v2_raw_message_inner::<M, _>(read, signing_data)?;
1591
1592 Ok((
1593 MavHeader {
1594 sequence: message.sequence(),
1595 system_id: message.system_id(),
1596 component_id: message.component_id(),
1597 },
1598 M::parse(MavlinkVersion::V2, message.message_id(), message.payload())?,
1599 ))
1600}
1601
1602#[cfg(feature = "tokio")]
1608pub async fn read_v2_msg_async<M: Message, R: tokio::io::AsyncRead + Unpin>(
1609 read: &mut AsyncPeekReader<R>,
1610) -> Result<(MavHeader, M), MessageReadError> {
1611 read_v2_msg_async_inner(read, None).await
1612}
1613
1614#[cfg(all(feature = "tokio", feature = "mav2-message-signing"))]
1620pub async fn read_v2_msg_async_signed<M: Message, R: tokio::io::AsyncRead + Unpin>(
1621 read: &mut AsyncPeekReader<R>,
1622 signing_data: Option<&SigningData>,
1623) -> Result<(MavHeader, M), MessageReadError> {
1624 read_v2_msg_async_inner(read, signing_data).await
1625}
1626
1627#[cfg(feature = "tokio")]
1628async fn read_v2_msg_async_inner<M: Message, R: tokio::io::AsyncRead + Unpin>(
1629 read: &mut AsyncPeekReader<R>,
1630 signing_data: Option<&SigningData>,
1631) -> Result<(MavHeader, M), MessageReadError> {
1632 let message = read_v2_raw_message_async_inner::<M, _>(read, signing_data).await?;
1633
1634 Ok((
1635 MavHeader {
1636 sequence: message.sequence(),
1637 system_id: message.system_id(),
1638 component_id: message.component_id(),
1639 },
1640 M::parse(MavlinkVersion::V2, message.message_id(), message.payload())?,
1641 ))
1642}
1643
1644#[cfg(all(feature = "embedded", not(feature = "std")))]
1649pub async fn read_v2_msg_async<M: Message, R: embedded_io_async::Read>(
1650 r: &mut R,
1651) -> Result<(MavHeader, M), MessageReadError> {
1652 let message = read_v2_raw_message_async::<M>(r).await?;
1653
1654 Ok((
1655 MavHeader {
1656 sequence: message.sequence(),
1657 system_id: message.system_id(),
1658 component_id: message.component_id(),
1659 },
1660 M::parse(
1661 MavlinkVersion::V2,
1662 u32::from(message.message_id()),
1663 message.payload(),
1664 )?,
1665 ))
1666}
1667
1668pub enum MAVLinkMessageRaw {
1670 V1(MAVLinkV1MessageRaw),
1671 V2(MAVLinkV2MessageRaw),
1672}
1673
1674impl MAVLinkMessageRaw {
1675 pub fn payload(&self) -> &[u8] {
1676 match self {
1677 Self::V1(msg) => msg.payload(),
1678 Self::V2(msg) => msg.payload(),
1679 }
1680 }
1681 pub fn sequence(&self) -> u8 {
1682 match self {
1683 Self::V1(msg) => msg.sequence(),
1684 Self::V2(msg) => msg.sequence(),
1685 }
1686 }
1687 pub fn system_id(&self) -> u8 {
1688 match self {
1689 Self::V1(msg) => msg.system_id(),
1690 Self::V2(msg) => msg.system_id(),
1691 }
1692 }
1693 pub fn component_id(&self) -> u8 {
1694 match self {
1695 Self::V1(msg) => msg.component_id(),
1696 Self::V2(msg) => msg.component_id(),
1697 }
1698 }
1699 pub fn message_id(&self) -> u32 {
1700 match self {
1701 Self::V1(msg) => u32::from(msg.message_id()),
1702 Self::V2(msg) => msg.message_id(),
1703 }
1704 }
1705 pub fn version(&self) -> MavlinkVersion {
1706 match self {
1707 Self::V1(_) => MavlinkVersion::V1,
1708 Self::V2(_) => MavlinkVersion::V2,
1709 }
1710 }
1711}
1712
1713#[inline]
1719pub fn read_any_raw_message<M: Message, R: Read>(
1720 reader: &mut PeekReader<R>,
1721) -> Result<MAVLinkMessageRaw, MessageReadError> {
1722 read_any_raw_message_inner::<M, R>(reader, None)
1723}
1724
1725#[cfg(feature = "mav2-message-signing")]
1731#[inline]
1732pub fn read_any_raw_message_signed<M: Message, R: Read>(
1733 reader: &mut PeekReader<R>,
1734 signing_data: Option<&SigningData>,
1735) -> Result<MAVLinkMessageRaw, MessageReadError> {
1736 read_any_raw_message_inner::<M, R>(reader, signing_data)
1737}
1738
1739#[allow(unused_variables)]
1740fn read_any_raw_message_inner<M: Message, R: Read>(
1741 reader: &mut PeekReader<R>,
1742 signing_data: Option<&SigningData>,
1743) -> Result<MAVLinkMessageRaw, MessageReadError> {
1744 loop {
1745 let version = loop {
1747 let byte = reader.peek_exact(1)?[0];
1748 if byte == MAV_STX {
1749 break MavlinkVersion::V1;
1750 }
1751 if byte == MAV_STX_V2 {
1752 break MavlinkVersion::V2;
1753 }
1754 reader.consume(1);
1755 };
1756 match version {
1757 MavlinkVersion::V1 => {
1758 if let Some(message) = try_decode_v1::<M, _>(reader)? {
1759 #[cfg(feature = "mav2-message-signing")]
1761 if let Some(signing) = signing_data {
1762 if signing.config.allow_unsigned {
1763 return Ok(MAVLinkMessageRaw::V1(message));
1764 }
1765 } else {
1766 return Ok(MAVLinkMessageRaw::V1(message));
1767 }
1768 #[cfg(not(feature = "mav2-message-signing"))]
1769 return Ok(MAVLinkMessageRaw::V1(message));
1770 }
1771
1772 reader.consume(1);
1773 }
1774 MavlinkVersion::V2 => {
1775 if let Some(message) = try_decode_v2::<M, _>(reader, signing_data)? {
1776 return Ok(MAVLinkMessageRaw::V2(message));
1777 }
1778 }
1779 }
1780 }
1781}
1782
1783#[cfg(feature = "tokio")]
1789pub async fn read_any_raw_message_async<M: Message, R: tokio::io::AsyncRead + Unpin>(
1790 reader: &mut AsyncPeekReader<R>,
1791) -> Result<MAVLinkMessageRaw, MessageReadError> {
1792 read_any_raw_message_async_inner::<M, R>(reader, None).await
1793}
1794
1795#[cfg(all(feature = "tokio", feature = "mav2-message-signing"))]
1803pub async fn read_any_raw_message_async_signed<M: Message, R: tokio::io::AsyncRead + Unpin>(
1804 reader: &mut AsyncPeekReader<R>,
1805 signing_data: Option<&SigningData>,
1806) -> Result<MAVLinkMessageRaw, MessageReadError> {
1807 read_any_raw_message_async_inner::<M, R>(reader, signing_data).await
1808}
1809
1810#[cfg(feature = "tokio")]
1811#[allow(unused_variables)]
1812async fn read_any_raw_message_async_inner<M: Message, R: tokio::io::AsyncRead + Unpin>(
1813 reader: &mut AsyncPeekReader<R>,
1814 signing_data: Option<&SigningData>,
1815) -> Result<MAVLinkMessageRaw, MessageReadError> {
1816 loop {
1817 let version = loop {
1819 let read = reader.read_u8().await?;
1820 if read == MAV_STX {
1821 break MavlinkVersion::V1;
1822 }
1823 if read == MAV_STX_V2 {
1824 break MavlinkVersion::V2;
1825 }
1826 };
1827
1828 match version {
1829 MavlinkVersion::V1 => {
1830 if let Some(message) = try_decode_v1_async::<M, _>(reader).await? {
1831 #[cfg(feature = "mav2-message-signing")]
1833 if let Some(signing) = signing_data {
1834 if signing.config.allow_unsigned {
1835 return Ok(MAVLinkMessageRaw::V1(message));
1836 }
1837 } else {
1838 return Ok(MAVLinkMessageRaw::V1(message));
1839 }
1840 #[cfg(not(feature = "mav2-message-signing"))]
1841 return Ok(MAVLinkMessageRaw::V1(message));
1842 }
1843 }
1844 MavlinkVersion::V2 => {
1845 if let Some(message) = try_decode_v2_async::<M, _>(reader, signing_data).await? {
1846 return Ok(MAVLinkMessageRaw::V2(message));
1847 }
1848 }
1849 }
1850 }
1851}
1852
1853#[inline]
1859pub fn read_any_msg<M: Message, R: Read>(
1860 read: &mut PeekReader<R>,
1861) -> Result<(MavHeader, M), MessageReadError> {
1862 read_any_msg_inner(read, None)
1863}
1864
1865#[cfg(feature = "mav2-message-signing")]
1873#[inline]
1874pub fn read_any_msg_signed<M: Message, R: Read>(
1875 read: &mut PeekReader<R>,
1876 signing_data: Option<&SigningData>,
1877) -> Result<(MavHeader, M), MessageReadError> {
1878 read_any_msg_inner(read, signing_data)
1879}
1880
1881fn read_any_msg_inner<M: Message, R: Read>(
1882 read: &mut PeekReader<R>,
1883 signing_data: Option<&SigningData>,
1884) -> Result<(MavHeader, M), MessageReadError> {
1885 let message = read_any_raw_message_inner::<M, _>(read, signing_data)?;
1886 Ok((
1887 MavHeader {
1888 sequence: message.sequence(),
1889 system_id: message.system_id(),
1890 component_id: message.component_id(),
1891 },
1892 M::parse(message.version(), message.message_id(), message.payload())?,
1893 ))
1894}
1895
1896#[cfg(feature = "tokio")]
1902pub async fn read_any_msg_async<M: Message, R: tokio::io::AsyncRead + Unpin>(
1903 read: &mut AsyncPeekReader<R>,
1904) -> Result<(MavHeader, M), MessageReadError> {
1905 read_any_msg_async_inner(read, None).await
1906}
1907
1908#[cfg(all(feature = "tokio", feature = "mav2-message-signing"))]
1916#[inline]
1917pub async fn read_any_msg_async_signed<M: Message, R: tokio::io::AsyncRead + Unpin>(
1918 read: &mut AsyncPeekReader<R>,
1919 signing_data: Option<&SigningData>,
1920) -> Result<(MavHeader, M), MessageReadError> {
1921 read_any_msg_async_inner(read, signing_data).await
1922}
1923
1924#[cfg(feature = "tokio")]
1925async fn read_any_msg_async_inner<M: Message, R: tokio::io::AsyncRead + Unpin>(
1926 read: &mut AsyncPeekReader<R>,
1927 signing_data: Option<&SigningData>,
1928) -> Result<(MavHeader, M), MessageReadError> {
1929 let message = read_any_raw_message_async_inner::<M, _>(read, signing_data).await?;
1930
1931 Ok((
1932 MavHeader {
1933 sequence: message.sequence(),
1934 system_id: message.system_id(),
1935 component_id: message.component_id(),
1936 },
1937 M::parse(message.version(), message.message_id(), message.payload())?,
1938 ))
1939}
1940
1941pub fn write_versioned_msg<M: Message, W: Write>(
1947 w: &mut W,
1948 version: MavlinkVersion,
1949 header: MavHeader,
1950 data: &M,
1951) -> Result<usize, MessageWriteError> {
1952 match version {
1953 MavlinkVersion::V2 => write_v2_msg(w, header, data),
1954 MavlinkVersion::V1 => write_v1_msg(w, header, data),
1955 }
1956}
1957
1958#[cfg(feature = "mav2-message-signing")]
1966pub fn write_versioned_msg_signed<M: Message, W: Write>(
1967 w: &mut W,
1968 version: MavlinkVersion,
1969 header: MavHeader,
1970 data: &M,
1971 signing_data: Option<&SigningData>,
1972) -> Result<usize, MessageWriteError> {
1973 match version {
1974 MavlinkVersion::V2 => write_v2_msg_signed(w, header, data, signing_data),
1975 MavlinkVersion::V1 => write_v1_msg(w, header, data),
1976 }
1977}
1978
1979#[cfg(feature = "tokio")]
1985pub async fn write_versioned_msg_async<M: Message, W: AsyncWrite + Unpin>(
1986 w: &mut W,
1987 version: MavlinkVersion,
1988 header: MavHeader,
1989 data: &M,
1990) -> Result<usize, MessageWriteError> {
1991 match version {
1992 MavlinkVersion::V2 => write_v2_msg_async(w, header, data).await,
1993 MavlinkVersion::V1 => write_v1_msg_async(w, header, data).await,
1994 }
1995}
1996
1997#[cfg(all(feature = "tokio", feature = "mav2-message-signing"))]
2005pub async fn write_versioned_msg_async_signed<M: Message, W: AsyncWrite + Unpin>(
2006 w: &mut W,
2007 version: MavlinkVersion,
2008 header: MavHeader,
2009 data: &M,
2010 signing_data: Option<&SigningData>,
2011) -> Result<usize, MessageWriteError> {
2012 match version {
2013 MavlinkVersion::V2 => write_v2_msg_async_signed(w, header, data, signing_data).await,
2014 MavlinkVersion::V1 => write_v1_msg_async(w, header, data).await,
2015 }
2016}
2017
2018#[cfg(all(feature = "embedded", not(feature = "std")))]
2023pub async fn write_versioned_msg_async<M: Message>(
2024 w: &mut impl embedded_io_async::Write,
2025 version: MavlinkVersion,
2026 header: MavHeader,
2027 data: &M,
2028) -> Result<usize, MessageWriteError> {
2029 match version {
2030 MavlinkVersion::V2 => write_v2_msg_async(w, header, data).await,
2031 MavlinkVersion::V1 => write_v1_msg_async(w, header, data).await,
2032 }
2033}
2034
2035pub fn write_v2_msg<M: Message, W: Write>(
2041 w: &mut W,
2042 header: MavHeader,
2043 data: &M,
2044) -> Result<usize, MessageWriteError> {
2045 let mut message_raw = MAVLinkV2MessageRaw::new();
2046 message_raw.serialize_message(header, data);
2047
2048 let payload_length: usize = message_raw.payload_length().into();
2049 let len = 1 + MAVLinkV2MessageRaw::HEADER_SIZE + payload_length + 2;
2050
2051 w.write_all(&message_raw.0[..len])?;
2052
2053 Ok(len)
2054}
2055
2056#[cfg(feature = "mav2-message-signing")]
2062pub fn write_v2_msg_signed<M: Message, W: Write>(
2063 w: &mut W,
2064 header: MavHeader,
2065 data: &M,
2066 signing_data: Option<&SigningData>,
2067) -> Result<usize, MessageWriteError> {
2068 let mut message_raw = MAVLinkV2MessageRaw::new();
2069
2070 let signature_len = if let Some(signing_data) = signing_data {
2071 if signing_data.config.sign_outgoing {
2072 message_raw.serialize_message_for_signing(header, data);
2073 signing_data.sign_message(&mut message_raw);
2074 MAVLinkV2MessageRaw::SIGNATURE_SIZE
2075 } else {
2076 message_raw.serialize_message(header, data);
2077 0
2078 }
2079 } else {
2080 message_raw.serialize_message(header, data);
2081 0
2082 };
2083
2084 let payload_length: usize = message_raw.payload_length().into();
2085 let len = 1 + MAVLinkV2MessageRaw::HEADER_SIZE + payload_length + 2 + signature_len;
2086
2087 w.write_all(&message_raw.0[..len])?;
2088
2089 Ok(len)
2090}
2091
2092#[cfg(feature = "tokio")]
2098pub async fn write_v2_msg_async<M: Message, W: AsyncWrite + Unpin>(
2099 w: &mut W,
2100 header: MavHeader,
2101 data: &M,
2102) -> Result<usize, MessageWriteError> {
2103 let mut message_raw = MAVLinkV2MessageRaw::new();
2104 message_raw.serialize_message(header, data);
2105
2106 let payload_length: usize = message_raw.payload_length().into();
2107 let len = 1 + MAVLinkV2MessageRaw::HEADER_SIZE + payload_length + 2;
2108
2109 w.write_all(&message_raw.0[..len]).await?;
2110
2111 Ok(len)
2112}
2113
2114#[cfg(feature = "mav2-message-signing")]
2120#[cfg(feature = "tokio")]
2121pub async fn write_v2_msg_async_signed<M: Message, W: AsyncWrite + Unpin>(
2122 w: &mut W,
2123 header: MavHeader,
2124 data: &M,
2125 signing_data: Option<&SigningData>,
2126) -> Result<usize, MessageWriteError> {
2127 let mut message_raw = MAVLinkV2MessageRaw::new();
2128
2129 let signature_len = if let Some(signing_data) = signing_data {
2130 if signing_data.config.sign_outgoing {
2131 message_raw.serialize_message_for_signing(header, data);
2132 signing_data.sign_message(&mut message_raw);
2133 MAVLinkV2MessageRaw::SIGNATURE_SIZE
2134 } else {
2135 message_raw.serialize_message(header, data);
2136 0
2137 }
2138 } else {
2139 message_raw.serialize_message(header, data);
2140 0
2141 };
2142
2143 let payload_length: usize = message_raw.payload_length().into();
2144 let len = 1 + MAVLinkV2MessageRaw::HEADER_SIZE + payload_length + 2 + signature_len;
2145
2146 w.write_all(&message_raw.0[..len]).await?;
2147
2148 Ok(len)
2149}
2150
2151#[cfg(all(feature = "embedded", not(feature = "std")))]
2160pub async fn write_v2_msg_async<M: Message>(
2161 w: &mut impl embedded_io_async::Write,
2162 header: MavHeader,
2163 data: &M,
2164) -> Result<usize, MessageWriteError> {
2165 let mut message_raw = MAVLinkV2MessageRaw::new();
2166 message_raw.serialize_message(header, data);
2167
2168 let payload_length: usize = message_raw.payload_length().into();
2169 let len = 1 + MAVLinkV2MessageRaw::HEADER_SIZE + payload_length + 2;
2170
2171 w.write_all(&message_raw.0[..len])
2172 .await
2173 .map_err(|_| MessageWriteError::Io)?;
2174
2175 Ok(len)
2176}
2177
2178pub fn write_v1_msg<M: Message, W: Write>(
2184 w: &mut W,
2185 header: MavHeader,
2186 data: &M,
2187) -> Result<usize, MessageWriteError> {
2188 if data.message_id() > u8::MAX.into() {
2189 return Err(MessageWriteError::MAVLink2Only);
2190 }
2191 let mut message_raw = MAVLinkV1MessageRaw::new();
2192 message_raw.serialize_message(header, data);
2193
2194 let payload_length: usize = message_raw.payload_length().into();
2195 let len = 1 + MAVLinkV1MessageRaw::HEADER_SIZE + payload_length + 2;
2196
2197 w.write_all(&message_raw.0[..len])?;
2198
2199 Ok(len)
2200}
2201
2202#[cfg(feature = "tokio")]
2208pub async fn write_v1_msg_async<M: Message, W: AsyncWrite + Unpin>(
2209 w: &mut W,
2210 header: MavHeader,
2211 data: &M,
2212) -> Result<usize, MessageWriteError> {
2213 if data.message_id() > u8::MAX.into() {
2214 return Err(MessageWriteError::MAVLink2Only);
2215 }
2216 let mut message_raw = MAVLinkV1MessageRaw::new();
2217 message_raw.serialize_message(header, data);
2218
2219 let payload_length: usize = message_raw.payload_length().into();
2220 let len = 1 + MAVLinkV1MessageRaw::HEADER_SIZE + payload_length + 2;
2221
2222 w.write_all(&message_raw.0[..len]).await?;
2223
2224 Ok(len)
2225}
2226
2227#[cfg(all(feature = "embedded", not(feature = "std")))]
2232pub async fn write_v1_msg_async<M: Message>(
2233 w: &mut impl embedded_io_async::Write,
2234 header: MavHeader,
2235 data: &M,
2236) -> Result<usize, MessageWriteError> {
2237 if data.message_id() > u8::MAX.into() {
2238 return Err(MessageWriteError::MAVLink2Only);
2239 }
2240 let mut message_raw = MAVLinkV1MessageRaw::new();
2241 message_raw.serialize_message(header, data);
2242
2243 let payload_length: usize = message_raw.payload_length().into();
2244 let len = 1 + MAVLinkV1MessageRaw::HEADER_SIZE + payload_length + 2;
2245
2246 w.write_all(&message_raw.0[..len])
2247 .await
2248 .map_err(|_| MessageWriteError::Io)?;
2249
2250 Ok(len)
2251}