@@ -188,7 +188,7 @@ impl MavProfile {
188
188
#[ allow( unused_imports) ]
189
189
use bitflags:: bitflags;
190
190
191
- use mavlink_core:: { MavlinkVersion , Message , MessageData , bytes:: Bytes , bytes_mut:: BytesMut } ;
191
+ use mavlink_core:: { MavlinkVersion , Message , MessageData , bytes:: Bytes , bytes_mut:: BytesMut , types :: CharArray } ;
192
192
193
193
#[ cfg( feature = "serde" ) ]
194
194
use serde:: { Serialize , Deserialize } ;
@@ -948,6 +948,7 @@ pub enum MavType {
948
948
Char ,
949
949
Float ,
950
950
Double ,
951
+ CharArray ( usize ) ,
951
952
Array ( Box < MavType > , usize ) ,
952
953
}
953
954
@@ -968,16 +969,18 @@ impl MavType {
968
969
"float" => Some ( Float ) ,
969
970
"Double" => Some ( Double ) ,
970
971
"double" => Some ( Double ) ,
971
- _ => {
972
- if s. ends_with ( ']' ) {
973
- let start = s. find ( '[' ) ?;
974
- let size = s[ start + 1 ..( s. len ( ) - 1 ) ] . parse :: < usize > ( ) . ok ( ) ?;
975
- let mtype = Self :: parse_type ( & s[ 0 ..start] ) ?;
976
- Some ( Array ( Box :: new ( mtype) , size) )
977
- } else {
978
- None
979
- }
972
+ _ if s. starts_with ( "char[" ) => {
973
+ let start = s. find ( '[' ) ?;
974
+ let size = s[ start + 1 ..( s. len ( ) - 1 ) ] . parse :: < usize > ( ) . ok ( ) ?;
975
+ Some ( CharArray ( size) )
980
976
}
977
+ _ if s. ends_with ( ']' ) => {
978
+ let start = s. find ( '[' ) ?;
979
+ let size = s[ start + 1 ..( s. len ( ) - 1 ) ] . parse :: < usize > ( ) . ok ( ) ?;
980
+ let mtype = Self :: parse_type ( & s[ 0 ..start] ) ?;
981
+ Some ( Array ( Box :: new ( mtype) , size) )
982
+ }
983
+ _ => None ,
981
984
}
982
985
}
983
986
@@ -997,6 +1000,15 @@ impl MavType {
997
1000
Int64 => quote ! { #val = #buf. get_i64_le( ) ; } ,
998
1001
Float => quote ! { #val = #buf. get_f32_le( ) ; } ,
999
1002
Double => quote ! { #val = #buf. get_f64_le( ) ; } ,
1003
+ CharArray ( size) => {
1004
+ quote ! {
1005
+ let mut tmp = [ 0_u8 ; #size] ;
1006
+ for v in & mut tmp {
1007
+ * v = #buf. get_u8( ) ;
1008
+ }
1009
+ #val = CharArray :: new( tmp) ;
1010
+ }
1011
+ }
1000
1012
Array ( t, _) => {
1001
1013
let r = t. rust_reader ( & quote ! ( let val) , buf) ;
1002
1014
quote ! {
@@ -1025,6 +1037,14 @@ impl MavType {
1025
1037
UInt64 => quote ! { #buf. put_u64_le( #val) ; } ,
1026
1038
Int64 => quote ! { #buf. put_i64_le( #val) ; } ,
1027
1039
Double => quote ! { #buf. put_f64_le( #val) ; } ,
1040
+ CharArray ( _) => {
1041
+ let w = Char . rust_writer ( & quote ! ( * val) , buf) ;
1042
+ quote ! {
1043
+ for val in & #val {
1044
+ #w
1045
+ }
1046
+ }
1047
+ }
1028
1048
Array ( t, _size) => {
1029
1049
let w = t. rust_writer ( & quote ! ( * val) , buf) ;
1030
1050
quote ! {
@@ -1044,6 +1064,7 @@ impl MavType {
1044
1064
UInt16 | Int16 => 2 ,
1045
1065
UInt32 | Int32 | Float => 4 ,
1046
1066
UInt64 | Int64 | Double => 8 ,
1067
+ CharArray ( size) => * size,
1047
1068
Array ( t, size) => t. len ( ) * size,
1048
1069
}
1049
1070
}
@@ -1052,7 +1073,7 @@ impl MavType {
1052
1073
fn order_len ( & self ) -> usize {
1053
1074
use self :: MavType :: * ;
1054
1075
match self {
1055
- UInt8MavlinkVersion | UInt8 | Int8 | Char => 1 ,
1076
+ UInt8MavlinkVersion | UInt8 | Int8 | Char | CharArray ( _ ) => 1 ,
1056
1077
UInt16 | Int16 => 2 ,
1057
1078
UInt32 | Int32 | Float => 4 ,
1058
1079
UInt64 | Int64 | Double => 8 ,
@@ -1076,6 +1097,7 @@ impl MavType {
1076
1097
UInt64 => "uint64_t" . into ( ) ,
1077
1098
Int64 => "int64_t" . into ( ) ,
1078
1099
Double => "double" . into ( ) ,
1100
+ CharArray ( _) => "char" . into ( ) ,
1079
1101
Array ( t, _) => t. primitive_type ( ) ,
1080
1102
}
1081
1103
}
@@ -1096,6 +1118,7 @@ impl MavType {
1096
1118
UInt64 => "u64" . into ( ) ,
1097
1119
Int64 => "i64" . into ( ) ,
1098
1120
Double => "f64" . into ( ) ,
1121
+ CharArray ( size) => format ! ( "CharArray<{}>" , size) ,
1099
1122
Array ( t, size) => format ! ( "[{};{}]" , t. rust_type( ) , size) ,
1100
1123
}
1101
1124
}
@@ -1114,6 +1137,7 @@ impl MavType {
1114
1137
UInt64 => quote ! ( 0_u64 ) ,
1115
1138
Int64 => quote ! ( 0_i64 ) ,
1116
1139
Double => quote ! ( 0.0_f64 ) ,
1140
+ CharArray ( size) => quote ! ( CharArray :: new( [ 0_u8 ; #size] ) ) ,
1117
1141
Array ( ty, size) => {
1118
1142
let default_value = ty. emit_default_value ( ) ;
1119
1143
quote ! ( [ #default_value; #size] )
@@ -1564,7 +1588,7 @@ pub fn extra_crc(msg: &MavMessage) -> u8 {
1564
1588
crc. digest ( field. name . as_bytes ( ) ) ;
1565
1589
}
1566
1590
crc. digest ( b" " ) ;
1567
- if let MavType :: Array ( _, size) = field. mavtype {
1591
+ if let MavType :: Array ( _, size) | MavType :: CharArray ( size ) = field. mavtype {
1568
1592
crc. digest ( & [ size as u8 ] ) ;
1569
1593
}
1570
1594
}
0 commit comments