@@ -221,14 +221,11 @@ impl<M: Message> MavFrame<M> {
221
221
MavlinkVersion :: V1 => buf. get_u8 ( ) . into ( ) ,
222
222
} ;
223
223
224
- match M :: parse ( version, msg_id, buf. remaining_bytes ( ) ) {
225
- Ok ( msg) => Ok ( Self {
226
- header,
227
- msg,
228
- protocol_version : version,
229
- } ) ,
230
- Err ( err) => Err ( err) ,
231
- }
224
+ M :: parse ( version, msg_id, buf. remaining_bytes ( ) ) . map ( |msg| Self {
225
+ header,
226
+ msg,
227
+ protocol_version : version,
228
+ } )
232
229
}
233
230
234
231
/// Return the frame header
@@ -474,22 +471,18 @@ pub fn read_v1_msg<M: Message, R: Read>(
474
471
) -> Result < ( MavHeader , M ) , error:: MessageReadError > {
475
472
let message = read_v1_raw_message :: < M , _ > ( r) ?;
476
473
477
- M :: parse (
478
- MavlinkVersion :: V1 ,
479
- u32:: from ( message. message_id ( ) ) ,
480
- message. payload ( ) ,
481
- )
482
- . map ( |msg| {
483
- (
484
- MavHeader {
485
- sequence : message. sequence ( ) ,
486
- system_id : message. system_id ( ) ,
487
- component_id : message. component_id ( ) ,
488
- } ,
489
- msg,
490
- )
491
- } )
492
- . map_err ( |err| err. into ( ) )
474
+ Ok ( (
475
+ MavHeader {
476
+ sequence : message. sequence ( ) ,
477
+ system_id : message. system_id ( ) ,
478
+ component_id : message. component_id ( ) ,
479
+ } ,
480
+ M :: parse (
481
+ MavlinkVersion :: V1 ,
482
+ u32:: from ( message. message_id ( ) ) ,
483
+ message. payload ( ) ,
484
+ ) ?,
485
+ ) )
493
486
}
494
487
495
488
/// Async read a MAVLink v1 message from a Read stream.
@@ -502,22 +495,18 @@ pub async fn read_v1_msg_async<M: Message>(
502
495
) -> Result < ( MavHeader , M ) , error:: MessageReadError > {
503
496
let message = read_v1_raw_message_async :: < M > ( r) . await ?;
504
497
505
- M :: parse (
506
- MavlinkVersion :: V1 ,
507
- u32:: from ( message. message_id ( ) ) ,
508
- message. payload ( ) ,
509
- )
510
- . map ( |msg| {
511
- (
512
- MavHeader {
513
- sequence : message. sequence ( ) ,
514
- system_id : message. system_id ( ) ,
515
- component_id : message. component_id ( ) ,
516
- } ,
517
- msg,
518
- )
519
- } )
520
- . map_err ( |err| err. into ( ) )
498
+ Ok ( (
499
+ MavHeader {
500
+ sequence : message. sequence ( ) ,
501
+ system_id : message. system_id ( ) ,
502
+ component_id : message. component_id ( ) ,
503
+ } ,
504
+ M :: parse (
505
+ MavlinkVersion :: V1 ,
506
+ u32:: from ( message. message_id ( ) ) ,
507
+ message. payload ( ) ,
508
+ ) ?,
509
+ ) )
521
510
}
522
511
523
512
const MAVLINK_IFLAG_SIGNED : u8 = 0x01 ;
@@ -818,18 +807,14 @@ pub fn read_v2_msg<M: Message, R: Read>(
818
807
) -> Result < ( MavHeader , M ) , error:: MessageReadError > {
819
808
let message = read_v2_raw_message :: < M , _ > ( read) ?;
820
809
821
- M :: parse ( MavlinkVersion :: V2 , message. message_id ( ) , message. payload ( ) )
822
- . map ( |msg| {
823
- (
824
- MavHeader {
825
- sequence : message. sequence ( ) ,
826
- system_id : message. system_id ( ) ,
827
- component_id : message. component_id ( ) ,
828
- } ,
829
- msg,
830
- )
831
- } )
832
- . map_err ( |err| err. into ( ) )
810
+ Ok ( (
811
+ MavHeader {
812
+ sequence : message. sequence ( ) ,
813
+ system_id : message. system_id ( ) ,
814
+ component_id : message. component_id ( ) ,
815
+ } ,
816
+ M :: parse ( MavlinkVersion :: V2 , message. message_id ( ) , message. payload ( ) ) ?,
817
+ ) )
833
818
}
834
819
835
820
/// Async read a MAVLink v2 message from a Read stream.
@@ -839,18 +824,14 @@ pub async fn read_v2_msg_async<M: Message, R: tokio::io::AsyncReadExt + Unpin>(
839
824
) -> Result < ( MavHeader , M ) , error:: MessageReadError > {
840
825
let message = read_v2_raw_message_async :: < M , _ > ( read) . await ?;
841
826
842
- M :: parse ( MavlinkVersion :: V2 , message. message_id ( ) , message. payload ( ) )
843
- . map ( |msg| {
844
- (
845
- MavHeader {
846
- sequence : message. sequence ( ) ,
847
- system_id : message. system_id ( ) ,
848
- component_id : message. component_id ( ) ,
849
- } ,
850
- msg,
851
- )
852
- } )
853
- . map_err ( |err| err. into ( ) )
827
+ Ok ( (
828
+ MavHeader {
829
+ sequence : message. sequence ( ) ,
830
+ system_id : message. system_id ( ) ,
831
+ component_id : message. component_id ( ) ,
832
+ } ,
833
+ M :: parse ( MavlinkVersion :: V2 , message. message_id ( ) , message. payload ( ) ) ?,
834
+ ) )
854
835
}
855
836
856
837
/// Async read a MAVLink v2 message from a Read stream.
@@ -863,22 +844,18 @@ pub async fn read_v2_msg_async<M: Message, R: embedded_io_async::Read>(
863
844
) -> Result < ( MavHeader , M ) , error:: MessageReadError > {
864
845
let message = read_v2_raw_message_async :: < M > ( r) . await ?;
865
846
866
- M :: parse (
867
- MavlinkVersion :: V2 ,
868
- u32:: from ( message. message_id ( ) ) ,
869
- message. payload ( ) ,
870
- )
871
- . map ( |msg| {
872
- (
873
- MavHeader {
874
- sequence : message. sequence ( ) ,
875
- system_id : message. system_id ( ) ,
876
- component_id : message. component_id ( ) ,
877
- } ,
878
- msg,
879
- )
880
- } )
881
- . map_err ( |err| err. into ( ) )
847
+ Ok ( (
848
+ MavHeader {
849
+ sequence : message. sequence ( ) ,
850
+ system_id : message. system_id ( ) ,
851
+ component_id : message. component_id ( ) ,
852
+ } ,
853
+ M :: parse (
854
+ MavlinkVersion :: V2 ,
855
+ u32:: from ( message. message_id ( ) ) ,
856
+ message. payload ( ) ,
857
+ ) ?,
858
+ ) )
882
859
}
883
860
884
861
/// Write a message using the given mavlink version
0 commit comments