@@ -188,7 +188,7 @@ impl MavProfile {
188188 #[ allow( unused_imports) ]
189189 use bitflags:: bitflags;
190190
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 } ;
192192
193193 #[ cfg( feature = "serde" ) ]
194194 use serde:: { Serialize , Deserialize } ;
@@ -948,6 +948,7 @@ pub enum MavType {
948948 Char ,
949949 Float ,
950950 Double ,
951+ CharArray ( usize ) ,
951952 Array ( Box < MavType > , usize ) ,
952953}
953954
@@ -968,16 +969,18 @@ impl MavType {
968969 "float" => Some ( Float ) ,
969970 "Double" => Some ( Double ) ,
970971 "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) )
980976 }
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 ,
981984 }
982985 }
983986
@@ -997,6 +1000,15 @@ impl MavType {
9971000 Int64 => quote ! { #val = #buf. get_i64_le( ) ; } ,
9981001 Float => quote ! { #val = #buf. get_f32_le( ) ; } ,
9991002 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+ }
10001012 Array ( t, _) => {
10011013 let r = t. rust_reader ( & quote ! ( let val) , buf) ;
10021014 quote ! {
@@ -1025,6 +1037,14 @@ impl MavType {
10251037 UInt64 => quote ! { #buf. put_u64_le( #val) ; } ,
10261038 Int64 => quote ! { #buf. put_i64_le( #val) ; } ,
10271039 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+ }
10281048 Array ( t, _size) => {
10291049 let w = t. rust_writer ( & quote ! ( * val) , buf) ;
10301050 quote ! {
@@ -1044,6 +1064,7 @@ impl MavType {
10441064 UInt16 | Int16 => 2 ,
10451065 UInt32 | Int32 | Float => 4 ,
10461066 UInt64 | Int64 | Double => 8 ,
1067+ CharArray ( size) => * size,
10471068 Array ( t, size) => t. len ( ) * size,
10481069 }
10491070 }
@@ -1052,7 +1073,7 @@ impl MavType {
10521073 fn order_len ( & self ) -> usize {
10531074 use self :: MavType :: * ;
10541075 match self {
1055- UInt8MavlinkVersion | UInt8 | Int8 | Char => 1 ,
1076+ UInt8MavlinkVersion | UInt8 | Int8 | Char | CharArray ( _ ) => 1 ,
10561077 UInt16 | Int16 => 2 ,
10571078 UInt32 | Int32 | Float => 4 ,
10581079 UInt64 | Int64 | Double => 8 ,
@@ -1076,6 +1097,7 @@ impl MavType {
10761097 UInt64 => "uint64_t" . into ( ) ,
10771098 Int64 => "int64_t" . into ( ) ,
10781099 Double => "double" . into ( ) ,
1100+ CharArray ( _) => "char" . into ( ) ,
10791101 Array ( t, _) => t. primitive_type ( ) ,
10801102 }
10811103 }
@@ -1096,6 +1118,7 @@ impl MavType {
10961118 UInt64 => "u64" . into ( ) ,
10971119 Int64 => "i64" . into ( ) ,
10981120 Double => "f64" . into ( ) ,
1121+ CharArray ( size) => format ! ( "CharArray<{}>" , size) ,
10991122 Array ( t, size) => format ! ( "[{};{}]" , t. rust_type( ) , size) ,
11001123 }
11011124 }
@@ -1114,6 +1137,7 @@ impl MavType {
11141137 UInt64 => quote ! ( 0_u64 ) ,
11151138 Int64 => quote ! ( 0_i64 ) ,
11161139 Double => quote ! ( 0.0_f64 ) ,
1140+ CharArray ( size) => quote ! ( CharArray :: new( [ 0_u8 ; #size] ) ) ,
11171141 Array ( ty, size) => {
11181142 let default_value = ty. emit_default_value ( ) ;
11191143 quote ! ( [ #default_value; #size] )
@@ -1564,7 +1588,7 @@ pub fn extra_crc(msg: &MavMessage) -> u8 {
15641588 crc. digest ( field. name . as_bytes ( ) ) ;
15651589 }
15661590 crc. digest ( b" " ) ;
1567- if let MavType :: Array ( _, size) = field. mavtype {
1591+ if let MavType :: Array ( _, size) | MavType :: CharArray ( size ) = field. mavtype {
15681592 crc. digest ( & [ size as u8 ] ) ;
15691593 }
15701594 }
0 commit comments