@@ -57,17 +57,14 @@ impl MavProfile {
57
57
fn update_enums ( mut self ) -> Self {
58
58
for msg in self . messages . values ( ) {
59
59
for field in & msg. fields {
60
- if let Some ( ref enum_name) = field. enumtype {
61
- // it is an enum
62
- if let Some ( ref dsp) = field. display {
63
- // it is a bitmask
64
- if dsp == "bitmask" {
65
- // find the corresponding enum
66
- for enm in self . enums . values_mut ( ) {
67
- if enm. name == * enum_name {
68
- // this is the right enum
69
- enm. bitfield = Some ( field. mavtype . rust_primitive_type ( ) ) ;
70
- }
60
+ if let Some ( enum_name) = & field. enumtype {
61
+ // it is a bitmask
62
+ if let Some ( "bitmask" ) = & field. display . as_deref ( ) {
63
+ // find the corresponding enum
64
+ for enm in self . enums . values_mut ( ) {
65
+ if enm. name == * enum_name {
66
+ // this is the right enum
67
+ enm. bitfield = Some ( field. mavtype . rust_primitive_type ( ) ) ;
71
68
}
72
69
}
73
70
}
@@ -503,13 +500,13 @@ impl MavMessage {
503
500
fn emit_serialize_vars ( & self ) -> TokenStream {
504
501
let ser_vars = self . fields . iter ( ) . map ( |f| f. rust_writer ( ) ) ;
505
502
quote ! {
506
- let mut _tmp = BytesMut :: new( bytes) ;
503
+ let mut __tmp = BytesMut :: new( bytes) ;
507
504
#( #ser_vars) *
508
505
if matches!( version, MavlinkVersion :: V2 ) {
509
- let len = _tmp . len( ) ;
510
- crate :: remove_trailing_zeroes( & mut bytes[ ..len] )
506
+ let len = __tmp . len( ) ;
507
+ crate :: remove_trailing_zeroes( & bytes[ ..len] )
511
508
} else {
512
- _tmp . len( )
509
+ __tmp . len( )
513
510
}
514
511
}
515
512
}
@@ -528,21 +525,21 @@ impl MavMessage {
528
525
}
529
526
} else {
530
527
quote ! {
531
- let avail_len = _input . len( ) ;
528
+ let avail_len = __input . len( ) ;
532
529
533
530
let mut payload_buf = [ 0 ; Self :: ENCODED_LEN ] ;
534
531
let mut buf = if avail_len < Self :: ENCODED_LEN {
535
532
//copy available bytes into an oversized buffer filled with zeros
536
- payload_buf[ 0 ..avail_len] . copy_from_slice( _input ) ;
533
+ payload_buf[ 0 ..avail_len] . copy_from_slice( __input ) ;
537
534
Bytes :: new( & payload_buf)
538
535
} else {
539
536
// fast zero copy
540
- Bytes :: new( _input )
537
+ Bytes :: new( __input )
541
538
} ;
542
539
543
- let mut _struct = Self :: default ( ) ;
540
+ let mut __struct = Self :: default ( ) ;
544
541
#( #deser_vars) *
545
- Ok ( _struct )
542
+ Ok ( __struct )
546
543
}
547
544
}
548
545
}
@@ -607,7 +604,7 @@ impl MavMessage {
607
604
const EXTRA_CRC : u8 = #extra_crc;
608
605
const ENCODED_LEN : usize = #msg_encoded_len;
609
606
610
- fn deser( _version: MavlinkVersion , _input : & [ u8 ] ) -> Result <Self , ParserError > {
607
+ fn deser( _version: MavlinkVersion , __input : & [ u8 ] ) -> Result <Self , ParserError > {
611
608
#deser_vars
612
609
}
613
610
@@ -643,7 +640,7 @@ impl MavField {
643
640
if matches ! ( self . mavtype, MavType :: Array ( _, _) ) {
644
641
let rt = TokenStream :: from_str ( & self . mavtype . rust_type ( ) ) . unwrap ( ) ;
645
642
mavtype = quote ! ( #rt) ;
646
- } else if let Some ( ref enumname) = self . enumtype {
643
+ } else if let Some ( enumname) = & self . enumtype {
647
644
let en = TokenStream :: from_str ( enumname) . unwrap ( ) ;
648
645
mavtype = quote ! ( #en) ;
649
646
} else {
@@ -695,15 +692,15 @@ impl MavField {
695
692
}
696
693
let ts = TokenStream :: from_str ( & name) . unwrap ( ) ;
697
694
let name = quote ! ( #ts) ;
698
- let buf = format_ident ! ( "_tmp " ) ;
695
+ let buf = format_ident ! ( "__tmp " ) ;
699
696
self . mavtype . rust_writer ( & name, buf)
700
697
}
701
698
702
699
/// Emit reader
703
700
fn rust_reader ( & self ) -> TokenStream {
704
701
let _name = TokenStream :: from_str ( & self . name ) . unwrap ( ) ;
705
702
706
- let name = quote ! ( _struct . #_name) ;
703
+ let name = quote ! ( __struct . #_name) ;
707
704
let buf = format_ident ! ( "buf" ) ;
708
705
if let Some ( enum_name) = & self . enumtype {
709
706
// TODO: handle enum arrays properly, rather than just generating
@@ -1122,7 +1119,7 @@ pub fn parse_profile(
1122
1119
let attr = attr. unwrap ( ) ;
1123
1120
match stack. last ( ) {
1124
1121
Some ( & MavXmlElement :: Enum ) => {
1125
- if let b"name" = attr. key . into_inner ( ) {
1122
+ if attr. key . into_inner ( ) == b"name" {
1126
1123
mavenum. name = attr
1127
1124
. value
1128
1125
. clone ( )
@@ -1273,7 +1270,7 @@ pub fn parse_profile(
1273
1270
entry. description = Some ( s. replace ( '\n' , " " ) ) ;
1274
1271
}
1275
1272
( Some ( & Param ) , Some ( & Entry ) ) => {
1276
- if let Some ( ref mut params) = entry. params {
1273
+ if let Some ( params) = & mut entry. params {
1277
1274
// Some messages can jump between values, like:
1278
1275
// 0, 1, 2, 7
1279
1276
if params. len ( ) < paramid. unwrap ( ) {
@@ -1382,21 +1379,21 @@ pub fn extra_crc(msg: &MavMessage) -> u8 {
1382
1379
let mut crc = CRCu16 :: crc16mcrf4cc ( ) ;
1383
1380
1384
1381
crc. digest ( msg. name . as_bytes ( ) ) ;
1385
- crc. digest ( " " . as_bytes ( ) ) ;
1382
+ crc. digest ( b " ") ;
1386
1383
1387
1384
let mut f = msg. fields . clone ( ) ;
1388
1385
// only mavlink 1 fields should be part of the extra_crc
1389
1386
f. retain ( |f| !f. is_extension ) ;
1390
1387
f. sort_by ( |a, b| a. mavtype . compare ( & b. mavtype ) ) ;
1391
1388
for field in & f {
1392
1389
crc. digest ( field. mavtype . primitive_type ( ) . as_bytes ( ) ) ;
1393
- crc. digest ( " " . as_bytes ( ) ) ;
1390
+ crc. digest ( b " ") ;
1394
1391
if field. name == "mavtype" {
1395
- crc. digest ( "type" . as_bytes ( ) ) ;
1392
+ crc. digest ( b "type") ;
1396
1393
} else {
1397
1394
crc. digest ( field. name . as_bytes ( ) ) ;
1398
1395
}
1399
- crc. digest ( " " . as_bytes ( ) ) ;
1396
+ crc. digest ( b " ") ;
1400
1397
if let MavType :: Array ( _, size) = field. mavtype {
1401
1398
crc. digest ( & [ size as u8 ] ) ;
1402
1399
}
@@ -1443,31 +1440,25 @@ impl MavXmlFilter {
1443
1440
Ok ( content) => {
1444
1441
match content {
1445
1442
Event :: Start ( bytes) | Event :: Empty ( bytes) => {
1446
- let id = match identify_element ( bytes. name ( ) . into_inner ( ) ) {
1447
- None => {
1448
- panic ! (
1449
- "unexpected element {:?}" ,
1450
- String :: from_utf8_lossy( bytes. name( ) . into_inner( ) )
1451
- ) ;
1452
- }
1453
- Some ( kind) => kind,
1443
+ let Some ( id) = identify_element ( bytes. name ( ) . into_inner ( ) ) else {
1444
+ panic ! (
1445
+ "unexpected element {:?}" ,
1446
+ String :: from_utf8_lossy( bytes. name( ) . into_inner( ) )
1447
+ ) ;
1454
1448
} ;
1455
- if let MavXmlElement :: Extensions = id {
1449
+ if id == MavXmlElement :: Extensions {
1456
1450
self . extension_filter . is_in = true ;
1457
1451
}
1458
1452
}
1459
1453
Event :: End ( bytes) => {
1460
- let id = match identify_element ( bytes. name ( ) . into_inner ( ) ) {
1461
- None => {
1462
- panic ! (
1463
- "unexpected element {:?}" ,
1464
- String :: from_utf8_lossy( bytes. name( ) . into_inner( ) )
1465
- ) ;
1466
- }
1467
- Some ( kind) => kind,
1454
+ let Some ( id) = identify_element ( bytes. name ( ) . into_inner ( ) ) else {
1455
+ panic ! (
1456
+ "unexpected element {:?}" ,
1457
+ String :: from_utf8_lossy( bytes. name( ) . into_inner( ) )
1458
+ ) ;
1468
1459
} ;
1469
1460
1470
- if let MavXmlElement :: Message = id {
1461
+ if id == MavXmlElement :: Message {
1471
1462
self . extension_filter . is_in = false ;
1472
1463
}
1473
1464
}
0 commit comments