1#![cfg_attr(not(feature = "std"), no_std)]
23#![cfg_attr(docsrs, feature(doc_auto_cfg))]
24#![deny(clippy::all)]
25#![warn(clippy::use_self)]
26
27use core::result::Result;
28
29#[cfg(feature = "std")]
30use std::io::{Read, Write};
31
32pub mod utils;
33#[allow(unused_imports)]
34use utils::{remove_trailing_zeroes, RustDefault};
35
36#[cfg(feature = "serde")]
37use serde::{Deserialize, Serialize};
38
39pub mod peek_reader;
40use peek_reader::PeekReader;
41
42use crate::{bytes::Bytes, error::ParserError};
43
44use crc_any::CRCu16;
45
46#[doc(hidden)]
47pub mod bytes;
48#[doc(hidden)]
49pub mod bytes_mut;
50#[cfg(feature = "std")]
51mod connection;
52pub mod error;
53#[cfg(feature = "std")]
54pub use self::connection::{connect, Connectable, MavConnection};
55
56#[cfg(feature = "tokio-1")]
57mod async_connection;
58#[cfg(feature = "tokio-1")]
59pub use self::async_connection::{connect_async, AsyncConnectable, AsyncMavConnection};
60
61#[cfg(feature = "tokio-1")]
62pub mod async_peek_reader;
63#[cfg(feature = "tokio-1")]
64use async_peek_reader::AsyncPeekReader;
65#[cfg(feature = "tokio-1")]
66use tokio::io::{AsyncWrite, AsyncWriteExt};
67
68#[cfg(any(feature = "embedded", feature = "embedded-hal-02"))]
69pub mod embedded;
70#[cfg(any(feature = "embedded", feature = "embedded-hal-02"))]
71use embedded::{Read, Write};
72
73#[cfg(not(feature = "signing"))]
74type SigningData = ();
75#[cfg(feature = "signing")]
76mod signing;
77#[cfg(feature = "signing")]
78pub use self::signing::{SigningConfig, SigningData};
79#[cfg(feature = "signing")]
80use sha2::{Digest, Sha256};
81
82#[cfg(feature = "arbitrary")]
83use arbitrary::Arbitrary;
84
85#[cfg(any(feature = "std", feature = "tokio-1"))]
86mod connectable;
87
88#[cfg(any(feature = "std", feature = "tokio-1"))]
89pub use connectable::ConnectionAddress;
90
91#[cfg(feature = "direct-serial")]
92pub use connection::direct_serial::config::SerialConfig;
93
94#[cfg(feature = "tcp")]
95pub use connection::tcp::config::{TcpConfig, TcpMode};
96
97#[cfg(feature = "udp")]
98pub use connection::udp::config::{UdpConfig, UdpMode};
99
100#[cfg(feature = "std")]
101pub use connection::file::config::FileConfig;
102
103pub const MAX_FRAME_SIZE: usize = 280;
107
108pub trait Message
113where
114 Self: Sized,
115{
116 fn message_id(&self) -> u32;
118
119 fn message_name(&self) -> &'static str;
121
122 fn target_system_id(&self) -> Option<u8>;
124
125 fn target_component_id(&self) -> Option<u8>;
127
128 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize;
130
131 fn parse(
133 version: MavlinkVersion,
134 msgid: u32,
135 payload: &[u8],
136 ) -> Result<Self, error::ParserError>;
137
138 fn message_id_from_name(name: &str) -> Option<u32>;
140 fn default_message_from_id(id: u32) -> Option<Self>;
142 #[cfg(feature = "arbitrary")]
144 fn random_message_from_id<R: rand::RngCore>(id: u32, rng: &mut R) -> Option<Self>;
145 fn extra_crc(id: u32) -> u8;
147}
148
149pub trait MessageData: Sized {
150 type Message: Message;
151
152 const ID: u32;
153 const NAME: &'static str;
154 const EXTRA_CRC: u8;
155 const ENCODED_LEN: usize;
156
157 fn ser(&self, version: MavlinkVersion, payload: &mut [u8]) -> usize;
158 fn deser(version: MavlinkVersion, payload: &[u8]) -> Result<Self, ParserError>;
159}
160
161#[derive(Debug, Copy, Clone, PartialEq, Eq)]
163#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
164#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
165pub struct MavHeader {
166 pub system_id: u8,
168 pub component_id: u8,
170 pub sequence: u8,
172}
173
174#[derive(Debug, Copy, Clone, PartialEq, Eq)]
176#[cfg_attr(feature = "serde", derive(Serialize))]
177#[cfg_attr(feature = "serde", serde(tag = "type"))]
178#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
179pub enum MavlinkVersion {
180 V1,
182 V2,
184}
185
186pub const MAV_STX: u8 = 0xFE;
188
189pub const MAV_STX_V2: u8 = 0xFD;
191
192impl Default for MavHeader {
195 fn default() -> Self {
196 Self {
197 system_id: 255,
198 component_id: 0,
199 sequence: 0,
200 }
201 }
202}
203
204#[derive(Debug, Clone)]
208#[cfg_attr(feature = "serde", derive(Serialize))]
209#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
210pub struct MavFrame<M: Message> {
211 pub header: MavHeader,
213 pub msg: M,
215 pub protocol_version: MavlinkVersion,
217}
218
219impl<M: Message> MavFrame<M> {
220 pub fn ser(&self, buf: &mut [u8]) -> usize {
224 let mut buf = bytes_mut::BytesMut::new(buf);
225
226 let mut payload_buf = [0u8; 255];
228 let payload_len = self.msg.ser(self.protocol_version, &mut payload_buf);
229
230 buf.put_u8(self.header.sequence);
249 buf.put_u8(self.header.system_id);
250 buf.put_u8(self.header.component_id);
251
252 match self.protocol_version {
254 MavlinkVersion::V2 => {
255 let bytes: [u8; 4] = self.msg.message_id().to_le_bytes();
256 buf.put_slice(&bytes[..3]);
257 }
258 MavlinkVersion::V1 => {
259 buf.put_u8(self.msg.message_id() as u8); }
261 }
262
263 buf.put_slice(&payload_buf[..payload_len]);
264 buf.len()
265 }
266
267 pub fn deser(version: MavlinkVersion, input: &[u8]) -> Result<Self, ParserError> {
271 let mut buf = Bytes::new(input);
272
273 let sequence = buf.get_u8();
283 let system_id = buf.get_u8();
284 let component_id = buf.get_u8();
285 let header = MavHeader {
286 system_id,
287 component_id,
288 sequence,
289 };
290
291 let msg_id = match version {
292 MavlinkVersion::V2 => buf.get_u24_le(),
293 MavlinkVersion::V1 => buf.get_u8().into(),
294 };
295
296 M::parse(version, msg_id, buf.remaining_bytes()).map(|msg| Self {
297 header,
298 msg,
299 protocol_version: version,
300 })
301 }
302
303 pub fn header(&self) -> MavHeader {
305 self.header
306 }
307}
308
309pub fn calculate_crc(data: &[u8], extra_crc: u8) -> u16 {
311 let mut crc_calculator = CRCu16::crc16mcrf4cc();
312 crc_calculator.digest(data);
313
314 crc_calculator.digest(&[extra_crc]);
315 crc_calculator.get_crc()
316}
317
318#[derive(Debug, Clone, Copy, PartialEq, Eq)]
319pub enum ReadVersion {
321 Single(MavlinkVersion),
323 Any,
325}
326
327impl ReadVersion {
328 #[cfg(feature = "std")]
329 fn from_conn_cfg<C: MavConnection<M>, M: Message>(conn: &C) -> Self {
330 if conn.allow_recv_any_version() {
331 Self::Any
332 } else {
333 conn.protocol_version().into()
334 }
335 }
336 #[cfg(feature = "tokio-1")]
337 fn from_async_conn_cfg<C: AsyncMavConnection<M>, M: Message + Sync + Send>(conn: &C) -> Self {
338 if conn.allow_recv_any_version() {
339 Self::Any
340 } else {
341 conn.protocol_version().into()
342 }
343 }
344}
345
346impl From<MavlinkVersion> for ReadVersion {
347 fn from(value: MavlinkVersion) -> Self {
348 Self::Single(value)
349 }
350}
351
352pub fn read_versioned_msg<M: Message, R: Read>(
354 r: &mut PeekReader<R>,
355 version: ReadVersion,
356) -> Result<(MavHeader, M), error::MessageReadError> {
357 match version {
358 ReadVersion::Single(MavlinkVersion::V2) => read_v2_msg(r),
359 ReadVersion::Single(MavlinkVersion::V1) => read_v1_msg(r),
360 ReadVersion::Any => read_any_msg(r),
361 }
362}
363
364pub fn read_raw_versioned_msg<M: Message, R: Read>(
366 r: &mut PeekReader<R>,
367 version: ReadVersion,
368) -> Result<MAVLinkMessageRaw, error::MessageReadError> {
369 match version {
370 ReadVersion::Single(MavlinkVersion::V2) => {
371 Ok(MAVLinkMessageRaw::V2(read_v2_raw_message::<M, _>(r)?))
372 }
373 ReadVersion::Single(MavlinkVersion::V1) => {
374 Ok(MAVLinkMessageRaw::V1(read_v1_raw_message::<M, _>(r)?))
375 }
376 ReadVersion::Any => read_any_raw_message::<M, _>(r),
377 }
378}
379
380#[cfg(feature = "tokio-1")]
382pub async fn read_versioned_msg_async<M: Message, R: tokio::io::AsyncRead + Unpin>(
383 r: &mut AsyncPeekReader<R>,
384 version: ReadVersion,
385) -> Result<(MavHeader, M), error::MessageReadError> {
386 match version {
387 ReadVersion::Single(MavlinkVersion::V2) => read_v2_msg_async(r).await,
388 ReadVersion::Single(MavlinkVersion::V1) => read_v1_msg_async(r).await,
389 ReadVersion::Any => read_any_msg_async(r).await,
390 }
391}
392
393#[cfg(feature = "tokio-1")]
395pub async fn read_raw_versioned_msg_async<M: Message, R: tokio::io::AsyncRead + Unpin>(
396 r: &mut AsyncPeekReader<R>,
397 version: ReadVersion,
398) -> Result<MAVLinkMessageRaw, error::MessageReadError> {
399 match version {
400 ReadVersion::Single(MavlinkVersion::V2) => Ok(MAVLinkMessageRaw::V2(
401 read_v2_raw_message_async::<M, _>(r).await?,
402 )),
403 ReadVersion::Single(MavlinkVersion::V1) => Ok(MAVLinkMessageRaw::V1(
404 read_v1_raw_message_async::<M, _>(r).await?,
405 )),
406 ReadVersion::Any => read_any_raw_message_async::<M, _>(r).await,
407 }
408}
409
410#[cfg(feature = "signing")]
415pub fn read_raw_versioned_msg_signed<M: Message, R: Read>(
416 r: &mut PeekReader<R>,
417 version: ReadVersion,
418 signing_data: Option<&SigningData>,
419) -> Result<MAVLinkMessageRaw, error::MessageReadError> {
420 match version {
421 ReadVersion::Single(MavlinkVersion::V2) => Ok(MAVLinkMessageRaw::V2(
422 read_v2_raw_message_inner::<M, _>(r, signing_data)?,
423 )),
424 ReadVersion::Single(MavlinkVersion::V1) => {
425 Ok(MAVLinkMessageRaw::V1(read_v1_raw_message::<M, _>(r)?))
426 }
427 ReadVersion::Any => read_any_raw_message_inner::<M, _>(r, signing_data),
428 }
429}
430
431#[cfg(feature = "signing")]
436pub fn read_versioned_msg_signed<M: Message, R: Read>(
437 r: &mut PeekReader<R>,
438 version: ReadVersion,
439 signing_data: Option<&SigningData>,
440) -> Result<(MavHeader, M), error::MessageReadError> {
441 match version {
442 ReadVersion::Single(MavlinkVersion::V2) => read_v2_msg_inner(r, signing_data),
443 ReadVersion::Single(MavlinkVersion::V1) => read_v1_msg(r),
444 ReadVersion::Any => read_any_msg_inner(r, signing_data),
445 }
446}
447
448#[cfg(all(feature = "tokio-1", feature = "signing"))]
453pub async fn read_raw_versioned_msg_async_signed<M: Message, R: tokio::io::AsyncRead + Unpin>(
454 r: &mut AsyncPeekReader<R>,
455 version: ReadVersion,
456 signing_data: Option<&SigningData>,
457) -> Result<MAVLinkMessageRaw, error::MessageReadError> {
458 match version {
459 ReadVersion::Single(MavlinkVersion::V2) => Ok(MAVLinkMessageRaw::V2(
460 read_v2_raw_message_async_inner::<M, _>(r, signing_data).await?,
461 )),
462 ReadVersion::Single(MavlinkVersion::V1) => Ok(MAVLinkMessageRaw::V1(
463 read_v1_raw_message_async::<M, _>(r).await?,
464 )),
465 ReadVersion::Any => read_any_raw_message_async_inner::<M, _>(r, signing_data).await,
466 }
467}
468
469#[cfg(all(feature = "tokio-1", feature = "signing"))]
474pub async fn read_versioned_msg_async_signed<M: Message, R: tokio::io::AsyncRead + Unpin>(
475 r: &mut AsyncPeekReader<R>,
476 version: ReadVersion,
477 signing_data: Option<&SigningData>,
478) -> Result<(MavHeader, M), error::MessageReadError> {
479 match version {
480 ReadVersion::Single(MavlinkVersion::V2) => read_v2_msg_async_inner(r, signing_data).await,
481 ReadVersion::Single(MavlinkVersion::V1) => read_v1_msg_async(r).await,
482 ReadVersion::Any => read_any_msg_async_inner(r, signing_data).await,
483 }
484}
485
486#[derive(Debug, Copy, Clone, PartialEq, Eq)]
487pub struct MAVLinkV1MessageRaw([u8; 1 + Self::HEADER_SIZE + 255 + 2]);
492
493impl Default for MAVLinkV1MessageRaw {
494 fn default() -> Self {
495 Self::new()
496 }
497}
498
499impl MAVLinkV1MessageRaw {
500 const HEADER_SIZE: usize = 5;
501
502 pub const fn new() -> Self {
504 Self([0; 1 + Self::HEADER_SIZE + 255 + 2])
505 }
506
507 pub const fn from_bytes_unparsed(bytes: [u8; 1 + Self::HEADER_SIZE + 255 + 2]) -> Self {
511 Self(bytes)
512 }
513
514 #[inline]
516 pub fn as_slice(&self) -> &[u8] {
517 &self.0
518 }
519
520 #[inline]
522 pub fn as_mut_slice(&mut self) -> &mut [u8] {
523 &mut self.0
524 }
525
526 #[inline]
528 pub fn into_inner(self) -> [u8; 1 + Self::HEADER_SIZE + 255 + 2] {
529 self.0
530 }
531
532 #[inline]
534 pub fn header(&self) -> &[u8] {
535 &self.0[1..=Self::HEADER_SIZE]
536 }
537
538 #[inline]
540 fn mut_header(&mut self) -> &mut [u8] {
541 &mut self.0[1..=Self::HEADER_SIZE]
542 }
543
544 #[inline]
546 pub fn payload_length(&self) -> u8 {
547 self.0[1]
548 }
549
550 #[inline]
552 pub fn sequence(&self) -> u8 {
553 self.0[2]
554 }
555
556 #[inline]
558 pub fn system_id(&self) -> u8 {
559 self.0[3]
560 }
561
562 #[inline]
564 pub fn component_id(&self) -> u8 {
565 self.0[4]
566 }
567
568 #[inline]
570 pub fn message_id(&self) -> u8 {
571 self.0[5]
572 }
573
574 #[inline]
576 pub fn payload(&self) -> &[u8] {
577 let payload_length: usize = self.payload_length().into();
578 &self.0[(1 + Self::HEADER_SIZE)..(1 + Self::HEADER_SIZE + payload_length)]
579 }
580
581 #[inline]
583 pub fn checksum(&self) -> u16 {
584 let payload_length: usize = self.payload_length().into();
585 u16::from_le_bytes([
586 self.0[1 + Self::HEADER_SIZE + payload_length],
587 self.0[1 + Self::HEADER_SIZE + payload_length + 1],
588 ])
589 }
590
591 #[inline]
592 fn mut_payload_and_checksum(&mut self) -> &mut [u8] {
593 let payload_length: usize = self.payload_length().into();
594 &mut self.0[(1 + Self::HEADER_SIZE)..(1 + Self::HEADER_SIZE + payload_length + 2)]
595 }
596
597 #[inline]
599 pub fn has_valid_crc<M: Message>(&self) -> bool {
600 let payload_length: usize = self.payload_length().into();
601 self.checksum()
602 == calculate_crc(
603 &self.0[1..(1 + Self::HEADER_SIZE + payload_length)],
604 M::extra_crc(self.message_id().into()),
605 )
606 }
607
608 pub fn raw_bytes(&self) -> &[u8] {
610 let payload_length = self.payload_length() as usize;
611 &self.0[..(1 + Self::HEADER_SIZE + payload_length + 2)]
612 }
613
614 fn serialize_stx_and_header_and_crc(
615 &mut self,
616 header: MavHeader,
617 msgid: u32,
618 payload_length: usize,
619 extra_crc: u8,
620 ) {
621 self.0[0] = MAV_STX;
622
623 let header_buf = self.mut_header();
624 header_buf.copy_from_slice(&[
625 payload_length as u8,
626 header.sequence,
627 header.system_id,
628 header.component_id,
629 msgid as u8,
630 ]);
631
632 let crc = calculate_crc(
633 &self.0[1..(1 + Self::HEADER_SIZE + payload_length)],
634 extra_crc,
635 );
636 self.0[(1 + Self::HEADER_SIZE + payload_length)
637 ..(1 + Self::HEADER_SIZE + payload_length + 2)]
638 .copy_from_slice(&crc.to_le_bytes());
639 }
640
641 pub fn serialize_message<M: Message>(&mut self, header: MavHeader, message: &M) {
643 let payload_buf = &mut self.0[(1 + Self::HEADER_SIZE)..(1 + Self::HEADER_SIZE + 255)];
644 let payload_length = message.ser(MavlinkVersion::V1, payload_buf);
645
646 let message_id = message.message_id();
647 self.serialize_stx_and_header_and_crc(
648 header,
649 message_id,
650 payload_length,
651 M::extra_crc(message_id),
652 );
653 }
654
655 pub fn serialize_message_data<D: MessageData>(&mut self, header: MavHeader, message_data: &D) {
656 let payload_buf = &mut self.0[(1 + Self::HEADER_SIZE)..(1 + Self::HEADER_SIZE + 255)];
657 let payload_length = message_data.ser(MavlinkVersion::V1, payload_buf);
658
659 self.serialize_stx_and_header_and_crc(header, D::ID, payload_length, D::EXTRA_CRC);
660 }
661}
662
663fn try_decode_v1<M: Message, R: Read>(
664 reader: &mut PeekReader<R>,
665) -> Result<Option<MAVLinkV1MessageRaw>, error::MessageReadError> {
666 let mut message = MAVLinkV1MessageRaw::new();
667 let whole_header_size = MAVLinkV1MessageRaw::HEADER_SIZE + 1;
668
669 message.0[0] = MAV_STX;
670 let header = &reader.peek_exact(whole_header_size)?[1..whole_header_size];
671 message.mut_header().copy_from_slice(header);
672 let packet_length = message.raw_bytes().len();
673 let payload_and_checksum = &reader.peek_exact(packet_length)?[whole_header_size..packet_length];
674 message
675 .mut_payload_and_checksum()
676 .copy_from_slice(payload_and_checksum);
677
678 if message.has_valid_crc::<M>() {
681 reader.consume(message.raw_bytes().len());
682 Ok(Some(message))
683 } else {
684 Ok(None)
685 }
686}
687
688#[cfg(feature = "tokio-1")]
689async fn try_decode_v1_async<M: Message, R: tokio::io::AsyncRead + Unpin>(
691 reader: &mut AsyncPeekReader<R>,
692) -> Result<Option<MAVLinkV1MessageRaw>, error::MessageReadError> {
693 let mut message = MAVLinkV1MessageRaw::new();
694
695 message.0[0] = MAV_STX;
696 let header = &reader.peek_exact(MAVLinkV1MessageRaw::HEADER_SIZE).await?
697 [..MAVLinkV1MessageRaw::HEADER_SIZE];
698 message.mut_header().copy_from_slice(header);
699 let packet_length = message.raw_bytes().len() - 1;
700 let payload_and_checksum =
701 &reader.peek_exact(packet_length).await?[MAVLinkV1MessageRaw::HEADER_SIZE..packet_length];
702 message
703 .mut_payload_and_checksum()
704 .copy_from_slice(payload_and_checksum);
705
706 if message.has_valid_crc::<M>() {
709 reader.consume(message.raw_bytes().len() - 1);
710 Ok(Some(message))
711 } else {
712 Ok(None)
713 }
714}
715
716pub fn read_v1_raw_message<M: Message, R: Read>(
718 reader: &mut PeekReader<R>,
719) -> Result<MAVLinkV1MessageRaw, error::MessageReadError> {
720 loop {
721 while reader.peek_exact(1)?[0] != MAV_STX {
723 reader.consume(1);
724 }
725
726 if let Some(msg) = try_decode_v1::<M, _>(reader)? {
727 return Ok(msg);
728 }
729
730 reader.consume(1);
731 }
732}
733
734#[cfg(feature = "tokio-1")]
736pub async fn read_v1_raw_message_async<M: Message, R: tokio::io::AsyncRead + Unpin>(
737 reader: &mut AsyncPeekReader<R>,
738) -> Result<MAVLinkV1MessageRaw, error::MessageReadError> {
739 loop {
740 loop {
741 if reader.read_u8().await? == MAV_STX {
743 break;
744 }
745 }
746
747 if let Some(message) = try_decode_v1_async::<M, _>(reader).await? {
748 return Ok(message);
749 }
750 }
751}
752
753#[cfg(feature = "embedded")]
759pub async fn read_v1_raw_message_async<M: Message>(
760 reader: &mut impl embedded_io_async::Read,
761) -> Result<MAVLinkV1MessageRaw, error::MessageReadError> {
762 loop {
763 let mut byte = [0u8];
765 loop {
766 reader
767 .read_exact(&mut byte)
768 .await
769 .map_err(|_| error::MessageReadError::Io)?;
770 if byte[0] == MAV_STX {
771 break;
772 }
773 }
774
775 let mut message = MAVLinkV1MessageRaw::new();
776
777 message.0[0] = MAV_STX;
778 reader
779 .read_exact(message.mut_header())
780 .await
781 .map_err(|_| error::MessageReadError::Io)?;
782 reader
783 .read_exact(message.mut_payload_and_checksum())
784 .await
785 .map_err(|_| error::MessageReadError::Io)?;
786
787 if message.has_valid_crc::<M>() {
790 return Ok(message);
791 }
792 }
793}
794
795pub fn read_v1_msg<M: Message, R: Read>(
797 r: &mut PeekReader<R>,
798) -> Result<(MavHeader, M), error::MessageReadError> {
799 let message = read_v1_raw_message::<M, _>(r)?;
800
801 Ok((
802 MavHeader {
803 sequence: message.sequence(),
804 system_id: message.system_id(),
805 component_id: message.component_id(),
806 },
807 M::parse(
808 MavlinkVersion::V1,
809 u32::from(message.message_id()),
810 message.payload(),
811 )?,
812 ))
813}
814
815#[cfg(feature = "tokio-1")]
817pub async fn read_v1_msg_async<M: Message, R: tokio::io::AsyncRead + Unpin>(
818 r: &mut AsyncPeekReader<R>,
819) -> Result<(MavHeader, M), error::MessageReadError> {
820 let message = read_v1_raw_message_async::<M, _>(r).await?;
821
822 Ok((
823 MavHeader {
824 sequence: message.sequence(),
825 system_id: message.system_id(),
826 component_id: message.component_id(),
827 },
828 M::parse(
829 MavlinkVersion::V1,
830 u32::from(message.message_id()),
831 message.payload(),
832 )?,
833 ))
834}
835
836#[cfg(feature = "embedded")]
841pub async fn read_v1_msg_async<M: Message>(
842 r: &mut impl embedded_io_async::Read,
843) -> Result<(MavHeader, M), error::MessageReadError> {
844 let message = read_v1_raw_message_async::<M>(r).await?;
845
846 Ok((
847 MavHeader {
848 sequence: message.sequence(),
849 system_id: message.system_id(),
850 component_id: message.component_id(),
851 },
852 M::parse(
853 MavlinkVersion::V1,
854 u32::from(message.message_id()),
855 message.payload(),
856 )?,
857 ))
858}
859
860const MAVLINK_IFLAG_SIGNED: u8 = 0x01;
861const MAVLINK_SUPPORTED_IFLAGS: u8 = MAVLINK_IFLAG_SIGNED;
862
863#[derive(Debug, Copy, Clone, PartialEq, Eq)]
864pub struct MAVLinkV2MessageRaw([u8; 1 + Self::HEADER_SIZE + 255 + 2 + Self::SIGNATURE_SIZE]);
869
870impl Default for MAVLinkV2MessageRaw {
871 fn default() -> Self {
872 Self::new()
873 }
874}
875
876impl MAVLinkV2MessageRaw {
877 const HEADER_SIZE: usize = 9;
878 const SIGNATURE_SIZE: usize = 13;
879
880 pub const fn new() -> Self {
882 Self([0; 1 + Self::HEADER_SIZE + 255 + 2 + Self::SIGNATURE_SIZE])
883 }
884
885 pub const fn from_bytes_unparsed(
889 bytes: [u8; 1 + Self::HEADER_SIZE + 255 + 2 + Self::SIGNATURE_SIZE],
890 ) -> Self {
891 Self(bytes)
892 }
893
894 #[inline]
896 pub fn as_slice(&self) -> &[u8] {
897 &self.0
898 }
899
900 #[inline]
902 pub fn as_mut_slice(&mut self) -> &mut [u8] {
903 &mut self.0
904 }
905
906 #[inline]
908 pub fn into_inner(self) -> [u8; 1 + Self::HEADER_SIZE + 255 + 2 + Self::SIGNATURE_SIZE] {
909 self.0
910 }
911
912 #[inline]
914 pub fn header(&self) -> &[u8] {
915 &self.0[1..=Self::HEADER_SIZE]
916 }
917
918 #[inline]
920 fn mut_header(&mut self) -> &mut [u8] {
921 &mut self.0[1..=Self::HEADER_SIZE]
922 }
923
924 #[inline]
926 pub fn payload_length(&self) -> u8 {
927 self.0[1]
928 }
929
930 #[inline]
934 pub fn incompatibility_flags(&self) -> u8 {
935 self.0[2]
936 }
937
938 #[inline]
942 pub fn incompatibility_flags_mut(&mut self) -> &mut u8 {
943 &mut self.0[2]
944 }
945
946 #[inline]
948 pub fn compatibility_flags(&self) -> u8 {
949 self.0[3]
950 }
951
952 #[inline]
954 pub fn sequence(&self) -> u8 {
955 self.0[4]
956 }
957
958 #[inline]
960 pub fn system_id(&self) -> u8 {
961 self.0[5]
962 }
963
964 #[inline]
966 pub fn component_id(&self) -> u8 {
967 self.0[6]
968 }
969
970 #[inline]
972 pub fn message_id(&self) -> u32 {
973 u32::from_le_bytes([self.0[7], self.0[8], self.0[9], 0])
974 }
975
976 #[inline]
978 pub fn payload(&self) -> &[u8] {
979 let payload_length: usize = self.payload_length().into();
980 &self.0[(1 + Self::HEADER_SIZE)..(1 + Self::HEADER_SIZE + payload_length)]
981 }
982
983 #[inline]
985 pub fn checksum(&self) -> u16 {
986 let payload_length: usize = self.payload_length().into();
987 u16::from_le_bytes([
988 self.0[1 + Self::HEADER_SIZE + payload_length],
989 self.0[1 + Self::HEADER_SIZE + payload_length + 1],
990 ])
991 }
992
993 #[cfg(feature = "signing")]
995 #[inline]
996 pub fn checksum_bytes(&self) -> &[u8] {
997 let checksum_offset = 1 + Self::HEADER_SIZE + self.payload_length() as usize;
998 &self.0[checksum_offset..(checksum_offset + 2)]
999 }
1000
1001 #[cfg(feature = "signing")]
1005 #[inline]
1006 pub fn signature_link_id(&self) -> u8 {
1007 let payload_length: usize = self.payload_length().into();
1008 self.0[1 + Self::HEADER_SIZE + payload_length + 2]
1009 }
1010
1011 #[cfg(feature = "signing")]
1013 #[inline]
1014 pub fn signature_link_id_mut(&mut self) -> &mut u8 {
1015 let payload_length: usize = self.payload_length().into();
1016 &mut self.0[1 + Self::HEADER_SIZE + payload_length + 2]
1017 }
1018
1019 #[cfg(feature = "signing")]
1025 #[inline]
1026 pub fn signature_timestamp(&self) -> u64 {
1027 let mut timestamp_bytes = [0u8; 8];
1028 timestamp_bytes[0..6].copy_from_slice(self.signature_timestamp_bytes());
1029 u64::from_le_bytes(timestamp_bytes)
1030 }
1031
1032 #[cfg(feature = "signing")]
1036 #[inline]
1037 pub fn signature_timestamp_bytes(&self) -> &[u8] {
1038 let payload_length: usize = self.payload_length().into();
1039 let timestamp_start = 1 + Self::HEADER_SIZE + payload_length + 3;
1040 &self.0[timestamp_start..(timestamp_start + 6)]
1041 }
1042
1043 #[cfg(feature = "signing")]
1045 #[inline]
1046 pub fn signature_timestamp_bytes_mut(&mut self) -> &mut [u8] {
1047 let payload_length: usize = self.payload_length().into();
1048 let timestamp_start = 1 + Self::HEADER_SIZE + payload_length + 3;
1049 &mut self.0[timestamp_start..(timestamp_start + 6)]
1050 }
1051
1052 #[cfg(feature = "signing")]
1056 #[inline]
1057 pub fn signature_value(&self) -> &[u8] {
1058 let payload_length: usize = self.payload_length().into();
1059 let signature_start = 1 + Self::HEADER_SIZE + payload_length + 3 + 6;
1060 &self.0[signature_start..(signature_start + 6)]
1061 }
1062
1063 #[cfg(feature = "signing")]
1065 #[inline]
1066 pub fn signature_value_mut(&mut self) -> &mut [u8] {
1067 let payload_length: usize = self.payload_length().into();
1068 let signature_start = 1 + Self::HEADER_SIZE + payload_length + 3 + 6;
1069 &mut self.0[signature_start..(signature_start + 6)]
1070 }
1071
1072 fn mut_payload_and_checksum_and_sign(&mut self) -> &mut [u8] {
1073 let payload_length: usize = self.payload_length().into();
1074
1075 let signature_size = if (self.incompatibility_flags() & MAVLINK_IFLAG_SIGNED) == 0 {
1077 0
1078 } else {
1079 Self::SIGNATURE_SIZE
1080 };
1081
1082 &mut self.0
1083 [(1 + Self::HEADER_SIZE)..(1 + Self::HEADER_SIZE + payload_length + signature_size + 2)]
1084 }
1085
1086 #[inline]
1088 pub fn has_valid_crc<M: Message>(&self) -> bool {
1089 let payload_length: usize = self.payload_length().into();
1090 self.checksum()
1091 == calculate_crc(
1092 &self.0[1..(1 + Self::HEADER_SIZE + payload_length)],
1093 M::extra_crc(self.message_id()),
1094 )
1095 }
1096
1097 #[cfg(feature = "signing")]
1101 pub fn calculate_signature(&self, secret_key: &[u8], target_buffer: &mut [u8; 6]) {
1102 let mut hasher = Sha256::new();
1103 hasher.update(secret_key);
1104 hasher.update([MAV_STX_V2]);
1105 hasher.update(self.header());
1106 hasher.update(self.payload());
1107 hasher.update(self.checksum_bytes());
1108 hasher.update([self.signature_link_id()]);
1109 hasher.update(self.signature_timestamp_bytes());
1110 target_buffer.copy_from_slice(&hasher.finalize()[0..6]);
1111 }
1112
1113 pub fn raw_bytes(&self) -> &[u8] {
1115 let payload_length = self.payload_length() as usize;
1116
1117 let signature_size = if (self.incompatibility_flags() & MAVLINK_IFLAG_SIGNED) == 0 {
1118 0
1119 } else {
1120 Self::SIGNATURE_SIZE
1121 };
1122
1123 &self.0[..(1 + Self::HEADER_SIZE + payload_length + signature_size + 2)]
1124 }
1125
1126 fn serialize_stx_and_header_and_crc(
1127 &mut self,
1128 header: MavHeader,
1129 msgid: u32,
1130 payload_length: usize,
1131 extra_crc: u8,
1132 incompat_flags: u8,
1133 ) {
1134 self.0[0] = MAV_STX_V2;
1135 let msgid_bytes = msgid.to_le_bytes();
1136
1137 let header_buf = self.mut_header();
1138 header_buf.copy_from_slice(&[
1139 payload_length as u8,
1140 incompat_flags,
1141 0, header.sequence,
1143 header.system_id,
1144 header.component_id,
1145 msgid_bytes[0],
1146 msgid_bytes[1],
1147 msgid_bytes[2],
1148 ]);
1149
1150 let crc = calculate_crc(
1151 &self.0[1..(1 + Self::HEADER_SIZE + payload_length)],
1152 extra_crc,
1153 );
1154 self.0[(1 + Self::HEADER_SIZE + payload_length)
1155 ..(1 + Self::HEADER_SIZE + payload_length + 2)]
1156 .copy_from_slice(&crc.to_le_bytes());
1157 }
1158
1159 pub fn serialize_message<M: Message>(&mut self, header: MavHeader, message: &M) {
1163 let payload_buf = &mut self.0[(1 + Self::HEADER_SIZE)..(1 + Self::HEADER_SIZE + 255)];
1164 let payload_length = message.ser(MavlinkVersion::V2, payload_buf);
1165
1166 let message_id = message.message_id();
1167 self.serialize_stx_and_header_and_crc(
1168 header,
1169 message_id,
1170 payload_length,
1171 M::extra_crc(message_id),
1172 0,
1173 );
1174 }
1175
1176 pub fn serialize_message_for_signing<M: Message>(&mut self, header: MavHeader, message: &M) {
1181 let payload_buf = &mut self.0[(1 + Self::HEADER_SIZE)..(1 + Self::HEADER_SIZE + 255)];
1182 let payload_length = message.ser(MavlinkVersion::V2, payload_buf);
1183
1184 let message_id = message.message_id();
1185 self.serialize_stx_and_header_and_crc(
1186 header,
1187 message_id,
1188 payload_length,
1189 M::extra_crc(message_id),
1190 MAVLINK_IFLAG_SIGNED,
1191 );
1192 }
1193
1194 pub fn serialize_message_data<D: MessageData>(&mut self, header: MavHeader, message_data: &D) {
1195 let payload_buf = &mut self.0[(1 + Self::HEADER_SIZE)..(1 + Self::HEADER_SIZE + 255)];
1196 let payload_length = message_data.ser(MavlinkVersion::V2, payload_buf);
1197
1198 self.serialize_stx_and_header_and_crc(header, D::ID, payload_length, D::EXTRA_CRC, 0);
1199 }
1200}
1201
1202#[allow(unused_variables)]
1203fn try_decode_v2<M: Message, R: Read>(
1204 reader: &mut PeekReader<R>,
1205 signing_data: Option<&SigningData>,
1206) -> Result<Option<MAVLinkV2MessageRaw>, error::MessageReadError> {
1207 let mut message = MAVLinkV2MessageRaw::new();
1208 let whole_header_size = MAVLinkV2MessageRaw::HEADER_SIZE + 1;
1209
1210 message.0[0] = MAV_STX_V2;
1211 let header = &reader.peek_exact(whole_header_size)?[1..whole_header_size];
1212 message.mut_header().copy_from_slice(header);
1213
1214 if message.incompatibility_flags() & !MAVLINK_SUPPORTED_IFLAGS > 0 {
1215 reader.consume(1);
1217 return Ok(None);
1218 }
1219
1220 let packet_length = message.raw_bytes().len();
1221 let payload_and_checksum_and_sign =
1222 &reader.peek_exact(packet_length)?[whole_header_size..packet_length];
1223 message
1224 .mut_payload_and_checksum_and_sign()
1225 .copy_from_slice(payload_and_checksum_and_sign);
1226
1227 if message.has_valid_crc::<M>() {
1228 reader.consume(message.raw_bytes().len());
1230 } else {
1231 reader.consume(1);
1232 return Ok(None);
1233 }
1234
1235 #[cfg(feature = "signing")]
1236 if let Some(signing_data) = signing_data {
1237 if !signing_data.verify_signature(&message) {
1238 return Ok(None);
1239 }
1240 }
1241
1242 Ok(Some(message))
1243}
1244
1245#[cfg(feature = "tokio-1")]
1246#[allow(unused_variables)]
1247async fn try_decode_v2_async<M: Message, R: tokio::io::AsyncRead + Unpin>(
1249 reader: &mut AsyncPeekReader<R>,
1250 signing_data: Option<&SigningData>,
1251) -> Result<Option<MAVLinkV2MessageRaw>, error::MessageReadError> {
1252 let mut message = MAVLinkV2MessageRaw::new();
1253
1254 message.0[0] = MAV_STX_V2;
1255 let header = &reader.peek_exact(MAVLinkV2MessageRaw::HEADER_SIZE).await?
1256 [..MAVLinkV2MessageRaw::HEADER_SIZE];
1257 message.mut_header().copy_from_slice(header);
1258
1259 if message.incompatibility_flags() & !MAVLINK_SUPPORTED_IFLAGS > 0 {
1260 return Ok(None);
1262 }
1263
1264 let packet_length = message.raw_bytes().len() - 1;
1265 let payload_and_checksum_and_sign =
1266 &reader.peek_exact(packet_length).await?[MAVLinkV2MessageRaw::HEADER_SIZE..packet_length];
1267 message
1268 .mut_payload_and_checksum_and_sign()
1269 .copy_from_slice(payload_and_checksum_and_sign);
1270
1271 if message.has_valid_crc::<M>() {
1272 reader.consume(message.raw_bytes().len() - 1);
1274 } else {
1275 return Ok(None);
1276 }
1277
1278 #[cfg(feature = "signing")]
1279 if let Some(signing_data) = signing_data {
1280 if !signing_data.verify_signature(&message) {
1281 return Ok(None);
1282 }
1283 }
1284
1285 Ok(Some(message))
1286}
1287
1288#[inline]
1290pub fn read_v2_raw_message<M: Message, R: Read>(
1291 reader: &mut PeekReader<R>,
1292) -> Result<MAVLinkV2MessageRaw, error::MessageReadError> {
1293 read_v2_raw_message_inner::<M, R>(reader, None)
1294}
1295
1296#[cfg(feature = "signing")]
1298#[inline]
1299pub fn read_v2_raw_message_signed<M: Message, R: Read>(
1300 reader: &mut PeekReader<R>,
1301 signing_data: Option<&SigningData>,
1302) -> Result<MAVLinkV2MessageRaw, error::MessageReadError> {
1303 read_v2_raw_message_inner::<M, R>(reader, signing_data)
1304}
1305
1306#[allow(unused_variables)]
1307fn read_v2_raw_message_inner<M: Message, R: Read>(
1308 reader: &mut PeekReader<R>,
1309 signing_data: Option<&SigningData>,
1310) -> Result<MAVLinkV2MessageRaw, error::MessageReadError> {
1311 loop {
1312 while reader.peek_exact(1)?[0] != MAV_STX_V2 {
1314 reader.consume(1);
1315 }
1316
1317 if let Some(message) = try_decode_v2::<M, _>(reader, signing_data)? {
1318 return Ok(message);
1319 }
1320 }
1321}
1322
1323#[cfg(feature = "tokio-1")]
1325pub async fn read_v2_raw_message_async<M: Message, R: tokio::io::AsyncRead + Unpin>(
1326 reader: &mut AsyncPeekReader<R>,
1327) -> Result<MAVLinkV2MessageRaw, error::MessageReadError> {
1328 read_v2_raw_message_async_inner::<M, R>(reader, None).await
1329}
1330
1331#[cfg(feature = "tokio-1")]
1332#[allow(unused_variables)]
1333async fn read_v2_raw_message_async_inner<M: Message, R: tokio::io::AsyncRead + Unpin>(
1334 reader: &mut AsyncPeekReader<R>,
1335 signing_data: Option<&SigningData>,
1336) -> Result<MAVLinkV2MessageRaw, error::MessageReadError> {
1337 loop {
1338 loop {
1339 if reader.read_u8().await? == MAV_STX_V2 {
1341 break;
1342 }
1343 }
1344
1345 if let Some(message) = try_decode_v2_async::<M, _>(reader, signing_data).await? {
1346 return Ok(message);
1347 }
1348 }
1349}
1350
1351#[cfg(all(feature = "tokio-1", feature = "signing"))]
1353pub async fn read_v2_raw_message_async_signed<M: Message, R: tokio::io::AsyncRead + Unpin>(
1354 reader: &mut AsyncPeekReader<R>,
1355 signing_data: Option<&SigningData>,
1356) -> Result<MAVLinkV2MessageRaw, error::MessageReadError> {
1357 read_v2_raw_message_async_inner::<M, R>(reader, signing_data).await
1358}
1359
1360#[cfg(feature = "embedded")]
1365pub async fn read_v2_raw_message_async<M: Message>(
1366 reader: &mut impl embedded_io_async::Read,
1367) -> Result<MAVLinkV2MessageRaw, error::MessageReadError> {
1368 loop {
1369 let mut byte = [0u8];
1371 loop {
1372 reader
1373 .read_exact(&mut byte)
1374 .await
1375 .map_err(|_| error::MessageReadError::Io)?;
1376 if byte[0] == MAV_STX_V2 {
1377 break;
1378 }
1379 }
1380
1381 let mut message = MAVLinkV2MessageRaw::new();
1382
1383 message.0[0] = MAV_STX_V2;
1384 reader
1385 .read_exact(message.mut_header())
1386 .await
1387 .map_err(|_| error::MessageReadError::Io)?;
1388
1389 if message.incompatibility_flags() & !MAVLINK_SUPPORTED_IFLAGS > 0 {
1390 continue;
1392 }
1393
1394 reader
1395 .read_exact(message.mut_payload_and_checksum_and_sign())
1396 .await
1397 .map_err(|_| error::MessageReadError::Io)?;
1398
1399 if message.has_valid_crc::<M>() {
1402 return Ok(message);
1403 }
1404 }
1405}
1406
1407#[inline]
1409pub fn read_v2_msg<M: Message, R: Read>(
1410 read: &mut PeekReader<R>,
1411) -> Result<(MavHeader, M), error::MessageReadError> {
1412 read_v2_msg_inner(read, None)
1413}
1414
1415#[cfg(feature = "signing")]
1417#[inline]
1418pub fn read_v2_msg_signed<M: Message, R: Read>(
1419 read: &mut PeekReader<R>,
1420 signing_data: Option<&SigningData>,
1421) -> Result<(MavHeader, M), error::MessageReadError> {
1422 read_v2_msg_inner(read, signing_data)
1423}
1424
1425fn read_v2_msg_inner<M: Message, R: Read>(
1426 read: &mut PeekReader<R>,
1427 signing_data: Option<&SigningData>,
1428) -> Result<(MavHeader, M), error::MessageReadError> {
1429 let message = read_v2_raw_message_inner::<M, _>(read, signing_data)?;
1430
1431 Ok((
1432 MavHeader {
1433 sequence: message.sequence(),
1434 system_id: message.system_id(),
1435 component_id: message.component_id(),
1436 },
1437 M::parse(MavlinkVersion::V2, message.message_id(), message.payload())?,
1438 ))
1439}
1440
1441#[cfg(feature = "tokio-1")]
1443pub async fn read_v2_msg_async<M: Message, R: tokio::io::AsyncRead + Unpin>(
1444 read: &mut AsyncPeekReader<R>,
1445) -> Result<(MavHeader, M), error::MessageReadError> {
1446 read_v2_msg_async_inner(read, None).await
1447}
1448
1449#[cfg(all(feature = "tokio-1", feature = "signing"))]
1451pub async fn read_v2_msg_async_signed<M: Message, R: tokio::io::AsyncRead + Unpin>(
1452 read: &mut AsyncPeekReader<R>,
1453 signing_data: Option<&SigningData>,
1454) -> Result<(MavHeader, M), error::MessageReadError> {
1455 read_v2_msg_async_inner(read, signing_data).await
1456}
1457
1458#[cfg(feature = "tokio-1")]
1459async fn read_v2_msg_async_inner<M: Message, R: tokio::io::AsyncRead + Unpin>(
1460 read: &mut AsyncPeekReader<R>,
1461 signing_data: Option<&SigningData>,
1462) -> Result<(MavHeader, M), error::MessageReadError> {
1463 let message = read_v2_raw_message_async_inner::<M, _>(read, signing_data).await?;
1464
1465 Ok((
1466 MavHeader {
1467 sequence: message.sequence(),
1468 system_id: message.system_id(),
1469 component_id: message.component_id(),
1470 },
1471 M::parse(MavlinkVersion::V2, message.message_id(), message.payload())?,
1472 ))
1473}
1474
1475#[cfg(feature = "embedded")]
1480pub async fn read_v2_msg_async<M: Message, R: embedded_io_async::Read>(
1481 r: &mut R,
1482) -> Result<(MavHeader, M), error::MessageReadError> {
1483 let message = read_v2_raw_message_async::<M>(r).await?;
1484
1485 Ok((
1486 MavHeader {
1487 sequence: message.sequence(),
1488 system_id: message.system_id(),
1489 component_id: message.component_id(),
1490 },
1491 M::parse(
1492 MavlinkVersion::V2,
1493 u32::from(message.message_id()),
1494 message.payload(),
1495 )?,
1496 ))
1497}
1498
1499pub enum MAVLinkMessageRaw {
1501 V1(MAVLinkV1MessageRaw),
1502 V2(MAVLinkV2MessageRaw),
1503}
1504
1505impl MAVLinkMessageRaw {
1506 pub fn payload(&self) -> &[u8] {
1507 match self {
1508 Self::V1(msg) => msg.payload(),
1509 Self::V2(msg) => msg.payload(),
1510 }
1511 }
1512 pub fn sequence(&self) -> u8 {
1513 match self {
1514 Self::V1(msg) => msg.sequence(),
1515 Self::V2(msg) => msg.sequence(),
1516 }
1517 }
1518 pub fn system_id(&self) -> u8 {
1519 match self {
1520 Self::V1(msg) => msg.system_id(),
1521 Self::V2(msg) => msg.system_id(),
1522 }
1523 }
1524 pub fn component_id(&self) -> u8 {
1525 match self {
1526 Self::V1(msg) => msg.component_id(),
1527 Self::V2(msg) => msg.component_id(),
1528 }
1529 }
1530 pub fn message_id(&self) -> u32 {
1531 match self {
1532 Self::V1(msg) => u32::from(msg.message_id()),
1533 Self::V2(msg) => msg.message_id(),
1534 }
1535 }
1536 pub fn version(&self) -> MavlinkVersion {
1537 match self {
1538 Self::V1(_) => MavlinkVersion::V1,
1539 Self::V2(_) => MavlinkVersion::V2,
1540 }
1541 }
1542}
1543
1544#[inline]
1546pub fn read_any_raw_message<M: Message, R: Read>(
1547 reader: &mut PeekReader<R>,
1548) -> Result<MAVLinkMessageRaw, error::MessageReadError> {
1549 read_any_raw_message_inner::<M, R>(reader, None)
1550}
1551
1552#[cfg(feature = "signing")]
1554#[inline]
1555pub fn read_any_raw_message_signed<M: Message, R: Read>(
1556 reader: &mut PeekReader<R>,
1557 signing_data: Option<&SigningData>,
1558) -> Result<MAVLinkMessageRaw, error::MessageReadError> {
1559 read_any_raw_message_inner::<M, R>(reader, signing_data)
1560}
1561
1562#[allow(unused_variables)]
1563fn read_any_raw_message_inner<M: Message, R: Read>(
1564 reader: &mut PeekReader<R>,
1565 signing_data: Option<&SigningData>,
1566) -> Result<MAVLinkMessageRaw, error::MessageReadError> {
1567 loop {
1568 let version = loop {
1570 let byte = reader.peek_exact(1)?[0];
1571 if byte == MAV_STX {
1572 break MavlinkVersion::V1;
1573 }
1574 if byte == MAV_STX_V2 {
1575 break MavlinkVersion::V2;
1576 }
1577 reader.consume(1);
1578 };
1579 match version {
1580 MavlinkVersion::V1 => {
1581 if let Some(message) = try_decode_v1::<M, _>(reader)? {
1582 #[cfg(feature = "signing")]
1584 if let Some(signing) = signing_data {
1585 if signing.config.allow_unsigned {
1586 return Ok(MAVLinkMessageRaw::V1(message));
1587 }
1588 } else {
1589 return Ok(MAVLinkMessageRaw::V1(message));
1590 }
1591 #[cfg(not(feature = "signing"))]
1592 return Ok(MAVLinkMessageRaw::V1(message));
1593 }
1594
1595 reader.consume(1);
1596 }
1597 MavlinkVersion::V2 => {
1598 if let Some(message) = try_decode_v2::<M, _>(reader, signing_data)? {
1599 return Ok(MAVLinkMessageRaw::V2(message));
1600 }
1601 }
1602 }
1603 }
1604}
1605
1606#[cfg(feature = "tokio-1")]
1608pub async fn read_any_raw_message_async<M: Message, R: tokio::io::AsyncRead + Unpin>(
1609 reader: &mut AsyncPeekReader<R>,
1610) -> Result<MAVLinkMessageRaw, error::MessageReadError> {
1611 read_any_raw_message_async_inner::<M, R>(reader, None).await
1612}
1613
1614#[cfg(all(feature = "tokio-1", feature = "signing"))]
1616pub async fn read_any_raw_message_async_signed<M: Message, R: tokio::io::AsyncRead + Unpin>(
1617 reader: &mut AsyncPeekReader<R>,
1618 signing_data: Option<&SigningData>,
1619) -> Result<MAVLinkMessageRaw, error::MessageReadError> {
1620 read_any_raw_message_async_inner::<M, R>(reader, signing_data).await
1621}
1622
1623#[cfg(feature = "tokio-1")]
1624#[allow(unused_variables)]
1625async fn read_any_raw_message_async_inner<M: Message, R: tokio::io::AsyncRead + Unpin>(
1626 reader: &mut AsyncPeekReader<R>,
1627 signing_data: Option<&SigningData>,
1628) -> Result<MAVLinkMessageRaw, error::MessageReadError> {
1629 loop {
1630 let version = loop {
1632 let read = reader.read_u8().await?;
1633 if read == MAV_STX {
1634 break MavlinkVersion::V1;
1635 }
1636 if read == MAV_STX_V2 {
1637 break MavlinkVersion::V2;
1638 }
1639 };
1640
1641 match version {
1642 MavlinkVersion::V1 => {
1643 if let Some(message) = try_decode_v1_async::<M, _>(reader).await? {
1644 #[cfg(feature = "signing")]
1646 if let Some(signing) = signing_data {
1647 if signing.config.allow_unsigned {
1648 return Ok(MAVLinkMessageRaw::V1(message));
1649 }
1650 } else {
1651 return Ok(MAVLinkMessageRaw::V1(message));
1652 }
1653 #[cfg(not(feature = "signing"))]
1654 return Ok(MAVLinkMessageRaw::V1(message));
1655 }
1656 }
1657 MavlinkVersion::V2 => {
1658 if let Some(message) = try_decode_v2_async::<M, _>(reader, signing_data).await? {
1659 return Ok(MAVLinkMessageRaw::V2(message));
1660 }
1661 }
1662 }
1663 }
1664}
1665
1666#[inline]
1668pub fn read_any_msg<M: Message, R: Read>(
1669 read: &mut PeekReader<R>,
1670) -> Result<(MavHeader, M), error::MessageReadError> {
1671 read_any_msg_inner(read, None)
1672}
1673
1674#[cfg(feature = "signing")]
1678#[inline]
1679pub fn read_any_msg_signed<M: Message, R: Read>(
1680 read: &mut PeekReader<R>,
1681 signing_data: Option<&SigningData>,
1682) -> Result<(MavHeader, M), error::MessageReadError> {
1683 read_any_msg_inner(read, signing_data)
1684}
1685
1686fn read_any_msg_inner<M: Message, R: Read>(
1687 read: &mut PeekReader<R>,
1688 signing_data: Option<&SigningData>,
1689) -> Result<(MavHeader, M), error::MessageReadError> {
1690 let message = read_any_raw_message_inner::<M, _>(read, signing_data)?;
1691 Ok((
1692 MavHeader {
1693 sequence: message.sequence(),
1694 system_id: message.system_id(),
1695 component_id: message.component_id(),
1696 },
1697 M::parse(message.version(), message.message_id(), message.payload())?,
1698 ))
1699}
1700
1701#[cfg(feature = "tokio-1")]
1703pub async fn read_any_msg_async<M: Message, R: tokio::io::AsyncRead + Unpin>(
1704 read: &mut AsyncPeekReader<R>,
1705) -> Result<(MavHeader, M), error::MessageReadError> {
1706 read_any_msg_async_inner(read, None).await
1707}
1708
1709#[cfg(all(feature = "tokio-1", feature = "signing"))]
1713#[inline]
1714pub async fn read_any_msg_async_signed<M: Message, R: tokio::io::AsyncRead + Unpin>(
1715 read: &mut AsyncPeekReader<R>,
1716 signing_data: Option<&SigningData>,
1717) -> Result<(MavHeader, M), error::MessageReadError> {
1718 read_any_msg_async_inner(read, signing_data).await
1719}
1720
1721#[cfg(feature = "tokio-1")]
1722async fn read_any_msg_async_inner<M: Message, R: tokio::io::AsyncRead + Unpin>(
1723 read: &mut AsyncPeekReader<R>,
1724 signing_data: Option<&SigningData>,
1725) -> Result<(MavHeader, M), error::MessageReadError> {
1726 let message = read_any_raw_message_async_inner::<M, _>(read, signing_data).await?;
1727
1728 Ok((
1729 MavHeader {
1730 sequence: message.sequence(),
1731 system_id: message.system_id(),
1732 component_id: message.component_id(),
1733 },
1734 M::parse(message.version(), message.message_id(), message.payload())?,
1735 ))
1736}
1737
1738pub fn write_versioned_msg<M: Message, W: Write>(
1740 w: &mut W,
1741 version: MavlinkVersion,
1742 header: MavHeader,
1743 data: &M,
1744) -> Result<usize, error::MessageWriteError> {
1745 match version {
1746 MavlinkVersion::V2 => write_v2_msg(w, header, data),
1747 MavlinkVersion::V1 => write_v1_msg(w, header, data),
1748 }
1749}
1750
1751#[cfg(feature = "signing")]
1755pub fn write_versioned_msg_signed<M: Message, W: Write>(
1756 w: &mut W,
1757 version: MavlinkVersion,
1758 header: MavHeader,
1759 data: &M,
1760 signing_data: Option<&SigningData>,
1761) -> Result<usize, error::MessageWriteError> {
1762 match version {
1763 MavlinkVersion::V2 => write_v2_msg_signed(w, header, data, signing_data),
1764 MavlinkVersion::V1 => write_v1_msg(w, header, data),
1765 }
1766}
1767
1768#[cfg(feature = "tokio-1")]
1770pub async fn write_versioned_msg_async<M: Message, W: AsyncWrite + Unpin>(
1771 w: &mut W,
1772 version: MavlinkVersion,
1773 header: MavHeader,
1774 data: &M,
1775) -> Result<usize, error::MessageWriteError> {
1776 match version {
1777 MavlinkVersion::V2 => write_v2_msg_async(w, header, data).await,
1778 MavlinkVersion::V1 => write_v1_msg_async(w, header, data).await,
1779 }
1780}
1781
1782#[cfg(all(feature = "tokio-1", feature = "signing"))]
1786pub async fn write_versioned_msg_async_signed<M: Message, W: AsyncWrite + Unpin>(
1787 w: &mut W,
1788 version: MavlinkVersion,
1789 header: MavHeader,
1790 data: &M,
1791 signing_data: Option<&SigningData>,
1792) -> Result<usize, error::MessageWriteError> {
1793 match version {
1794 MavlinkVersion::V2 => write_v2_msg_async_signed(w, header, data, signing_data).await,
1795 MavlinkVersion::V1 => write_v1_msg_async(w, header, data).await,
1796 }
1797}
1798
1799#[cfg(feature = "embedded")]
1804pub async fn write_versioned_msg_async<M: Message>(
1805 w: &mut impl embedded_io_async::Write,
1806 version: MavlinkVersion,
1807 header: MavHeader,
1808 data: &M,
1809) -> Result<usize, error::MessageWriteError> {
1810 match version {
1811 MavlinkVersion::V2 => write_v2_msg_async(w, header, data).await,
1812 MavlinkVersion::V1 => write_v1_msg_async(w, header, data).await,
1813 }
1814}
1815
1816pub fn write_v2_msg<M: Message, W: Write>(
1818 w: &mut W,
1819 header: MavHeader,
1820 data: &M,
1821) -> Result<usize, error::MessageWriteError> {
1822 let mut message_raw = MAVLinkV2MessageRaw::new();
1823 message_raw.serialize_message(header, data);
1824
1825 let payload_length: usize = message_raw.payload_length().into();
1826 let len = 1 + MAVLinkV2MessageRaw::HEADER_SIZE + payload_length + 2;
1827
1828 w.write_all(&message_raw.0[..len])?;
1829
1830 Ok(len)
1831}
1832
1833#[cfg(feature = "signing")]
1835pub fn write_v2_msg_signed<M: Message, W: Write>(
1836 w: &mut W,
1837 header: MavHeader,
1838 data: &M,
1839 signing_data: Option<&SigningData>,
1840) -> Result<usize, error::MessageWriteError> {
1841 let mut message_raw = MAVLinkV2MessageRaw::new();
1842
1843 let signature_len = if let Some(signing_data) = signing_data {
1844 if signing_data.config.sign_outgoing {
1845 message_raw.serialize_message_for_signing(header, data);
1846 signing_data.sign_message(&mut message_raw);
1847 MAVLinkV2MessageRaw::SIGNATURE_SIZE
1848 } else {
1849 message_raw.serialize_message(header, data);
1850 0
1851 }
1852 } else {
1853 message_raw.serialize_message(header, data);
1854 0
1855 };
1856
1857 let payload_length: usize = message_raw.payload_length().into();
1858 let len = 1 + MAVLinkV2MessageRaw::HEADER_SIZE + payload_length + 2 + signature_len;
1859
1860 w.write_all(&message_raw.0[..len])?;
1861
1862 Ok(len)
1863}
1864
1865#[cfg(feature = "tokio-1")]
1867pub async fn write_v2_msg_async<M: Message, W: AsyncWrite + Unpin>(
1868 w: &mut W,
1869 header: MavHeader,
1870 data: &M,
1871) -> Result<usize, error::MessageWriteError> {
1872 let mut message_raw = MAVLinkV2MessageRaw::new();
1873 message_raw.serialize_message(header, data);
1874
1875 let payload_length: usize = message_raw.payload_length().into();
1876 let len = 1 + MAVLinkV2MessageRaw::HEADER_SIZE + payload_length + 2;
1877
1878 w.write_all(&message_raw.0[..len]).await?;
1879
1880 Ok(len)
1881}
1882
1883#[cfg(feature = "signing")]
1885#[cfg(feature = "tokio-1")]
1886pub async fn write_v2_msg_async_signed<M: Message, W: AsyncWrite + Unpin>(
1887 w: &mut W,
1888 header: MavHeader,
1889 data: &M,
1890 signing_data: Option<&SigningData>,
1891) -> Result<usize, error::MessageWriteError> {
1892 let mut message_raw = MAVLinkV2MessageRaw::new();
1893
1894 let signature_len = if let Some(signing_data) = signing_data {
1895 if signing_data.config.sign_outgoing {
1896 message_raw.serialize_message_for_signing(header, data);
1897 signing_data.sign_message(&mut message_raw);
1898 MAVLinkV2MessageRaw::SIGNATURE_SIZE
1899 } else {
1900 message_raw.serialize_message(header, data);
1901 0
1902 }
1903 } else {
1904 message_raw.serialize_message(header, data);
1905 0
1906 };
1907
1908 let payload_length: usize = message_raw.payload_length().into();
1909 let len = 1 + MAVLinkV2MessageRaw::HEADER_SIZE + payload_length + 2 + signature_len;
1910
1911 w.write_all(&message_raw.0[..len]).await?;
1912
1913 Ok(len)
1914}
1915
1916#[cfg(feature = "embedded")]
1921pub async fn write_v2_msg_async<M: Message>(
1922 w: &mut impl embedded_io_async::Write,
1923 header: MavHeader,
1924 data: &M,
1925) -> Result<usize, error::MessageWriteError> {
1926 let mut message_raw = MAVLinkV2MessageRaw::new();
1927 message_raw.serialize_message(header, data);
1928
1929 let payload_length: usize = message_raw.payload_length().into();
1930 let len = 1 + MAVLinkV2MessageRaw::HEADER_SIZE + payload_length + 2;
1931
1932 w.write_all(&message_raw.0[..len])
1933 .await
1934 .map_err(|_| error::MessageWriteError::Io)?;
1935
1936 Ok(len)
1937}
1938
1939pub fn write_v1_msg<M: Message, W: Write>(
1941 w: &mut W,
1942 header: MavHeader,
1943 data: &M,
1944) -> Result<usize, error::MessageWriteError> {
1945 let mut message_raw = MAVLinkV1MessageRaw::new();
1946 message_raw.serialize_message(header, data);
1947
1948 let payload_length: usize = message_raw.payload_length().into();
1949 let len = 1 + MAVLinkV1MessageRaw::HEADER_SIZE + payload_length + 2;
1950
1951 w.write_all(&message_raw.0[..len])?;
1952
1953 Ok(len)
1954}
1955
1956#[cfg(feature = "tokio-1")]
1958pub async fn write_v1_msg_async<M: Message, W: AsyncWrite + Unpin>(
1959 w: &mut W,
1960 header: MavHeader,
1961 data: &M,
1962) -> Result<usize, error::MessageWriteError> {
1963 let mut message_raw = MAVLinkV1MessageRaw::new();
1964 message_raw.serialize_message(header, data);
1965
1966 let payload_length: usize = message_raw.payload_length().into();
1967 let len = 1 + MAVLinkV1MessageRaw::HEADER_SIZE + payload_length + 2;
1968
1969 w.write_all(&message_raw.0[..len]).await?;
1970
1971 Ok(len)
1972}
1973
1974#[cfg(feature = "embedded")]
1979pub async fn write_v1_msg_async<M: Message>(
1980 w: &mut impl embedded_io_async::Write,
1981 header: MavHeader,
1982 data: &M,
1983) -> Result<usize, error::MessageWriteError> {
1984 let mut message_raw = MAVLinkV1MessageRaw::new();
1985 message_raw.serialize_message(header, data);
1986
1987 let payload_length: usize = message_raw.payload_length().into();
1988 let len = 1 + MAVLinkV1MessageRaw::HEADER_SIZE + payload_length + 2;
1989
1990 w.write_all(&message_raw.0[..len])
1991 .await
1992 .map_err(|_| error::MessageWriteError::Io)?;
1993
1994 Ok(len)
1995}