Skip to content

Commit c05e756

Browse files
authored
refactor bytes module to be panic safe (#428)
* refactor bytes module to be panic safe Makes bytes module to be panic safe, which is part of the internal implementation (not the public API). Signed-off-by: Onur Özkan <[email protected]> * use no-std compatible errors in bytes Signed-off-by: Onur Özkan <[email protected]> --------- Signed-off-by: Onur Özkan <[email protected]>
1 parent 6ba4c18 commit c05e756

File tree

10 files changed

+152
-117
lines changed

10 files changed

+152
-117
lines changed

mavlink-bindgen/src/parser.rs

Lines changed: 13 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -1173,23 +1173,23 @@ impl MavType {
11731173
pub fn rust_reader(&self, val: &TokenStream, buf: Ident) -> TokenStream {
11741174
use self::MavType::*;
11751175
match self {
1176-
Char => quote! {#val = #buf.get_u8();},
1177-
UInt8 => quote! {#val = #buf.get_u8();},
1178-
UInt16 => quote! {#val = #buf.get_u16_le();},
1179-
UInt32 => quote! {#val = #buf.get_u32_le();},
1180-
UInt64 => quote! {#val = #buf.get_u64_le();},
1181-
UInt8MavlinkVersion => quote! {#val = #buf.get_u8();},
1182-
Int8 => quote! {#val = #buf.get_i8();},
1183-
Int16 => quote! {#val = #buf.get_i16_le();},
1184-
Int32 => quote! {#val = #buf.get_i32_le();},
1185-
Int64 => quote! {#val = #buf.get_i64_le();},
1186-
Float => quote! {#val = #buf.get_f32_le();},
1187-
Double => quote! {#val = #buf.get_f64_le();},
1176+
Char => quote! {#val = #buf.get_u8()?;},
1177+
UInt8 => quote! {#val = #buf.get_u8()?;},
1178+
UInt16 => quote! {#val = #buf.get_u16_le()?;},
1179+
UInt32 => quote! {#val = #buf.get_u32_le()?;},
1180+
UInt64 => quote! {#val = #buf.get_u64_le()?;},
1181+
UInt8MavlinkVersion => quote! {#val = #buf.get_u8()?;},
1182+
Int8 => quote! {#val = #buf.get_i8()?;},
1183+
Int16 => quote! {#val = #buf.get_i16_le()?;},
1184+
Int32 => quote! {#val = #buf.get_i32_le()?;},
1185+
Int64 => quote! {#val = #buf.get_i64_le()?;},
1186+
Float => quote! {#val = #buf.get_f32_le()?;},
1187+
Double => quote! {#val = #buf.get_f64_le()?;},
11881188
CharArray(size) => {
11891189
quote! {
11901190
let mut tmp = [0_u8; #size];
11911191
for v in &mut tmp {
1192-
*v = #buf.get_u8();
1192+
*v = #buf.get_u8()?;
11931193
}
11941194
#val = CharArray::new(tmp);
11951195
}

mavlink-bindgen/tests/snapshots/[email protected]

Lines changed: 5 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,6 @@
11
---
22
source: mavlink-bindgen/tests/e2e_snapshots.rs
3+
assertion_line: 26
34
expression: contents
45
---
56
#![doc = "MAVLink deprecated dialect."]
@@ -126,10 +127,10 @@ impl MessageData for PING_DATA {
126127
Bytes::new(__input)
127128
};
128129
let mut __struct = Self::default();
129-
__struct.time_usec = buf.get_u64_le();
130-
__struct.seq = buf.get_u32_le();
131-
__struct.target_system = buf.get_u8();
132-
__struct.target_component = buf.get_u8();
130+
__struct.time_usec = buf.get_u64_le()?;
131+
__struct.seq = buf.get_u32_le()?;
132+
__struct.target_system = buf.get_u8()?;
133+
__struct.target_component = buf.get_u8()?;
133134
Ok(__struct)
134135
}
135136
fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {

mavlink-bindgen/tests/snapshots/[email protected]

Lines changed: 6 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -91,12 +91,12 @@ impl MessageData for HEARTBEAT_DATA {
9191
Bytes::new(__input)
9292
};
9393
let mut __struct = Self::default();
94-
__struct.custom_mode = buf.get_u32_le();
95-
__struct.mavtype = buf.get_u8();
96-
__struct.autopilot = buf.get_u8();
97-
__struct.base_mode = buf.get_u8();
98-
__struct.system_status = buf.get_u8();
99-
__struct.mavlink_version = buf.get_u8();
94+
__struct.custom_mode = buf.get_u32_le()?;
95+
__struct.mavtype = buf.get_u8()?;
96+
__struct.autopilot = buf.get_u8()?;
97+
__struct.base_mode = buf.get_u8()?;
98+
__struct.system_status = buf.get_u8()?;
99+
__struct.mavlink_version = buf.get_u8()?;
100100
Ok(__struct)
101101
}
102102
fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {

mavlink-bindgen/tests/snapshots/e2e_snapshots__mav_bool.xml@mav_bool.rs.snap

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -91,14 +91,14 @@ impl MessageData for BOOL_TEST_MESSAGE_DATA {
9191
Bytes::new(__input)
9292
};
9393
let mut __struct = Self::default();
94-
let tmp = buf.get_u8();
94+
let tmp = buf.get_u8()?;
9595
__struct.bool_uint8 = MavBool::from_bits(tmp as <MavBool as Flags>::Bits).ok_or(
9696
::mavlink_core::error::ParserError::InvalidFlag {
9797
flag_type: "MavBool",
9898
value: tmp as u64,
9999
},
100100
)?;
101-
let tmp = buf.get_i8();
101+
let tmp = buf.get_i8()?;
102102
__struct.bool_int8 = MavBool::from_bits(tmp as <MavBool as Flags>::Bits).ok_or(
103103
::mavlink_core::error::ParserError::InvalidFlag {
104104
flag_type: "MavBool",

mavlink-bindgen/tests/snapshots/e2e_snapshots__no_field_description.xml@no_field_description.rs.snap

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,6 @@
11
---
22
source: mavlink-bindgen/tests/e2e_snapshots.rs
3+
assertion_line: 26
34
expression: contents
45
---
56
#![doc = "MAVLink no_field_description dialect."]
@@ -77,7 +78,7 @@ impl MessageData for CUBEPILOT_RAW_RC_DATA {
7778
};
7879
let mut __struct = Self::default();
7980
for v in &mut __struct.rc_raw {
80-
let val = buf.get_u8();
81+
let val = buf.get_u8()?;
8182
*v = val;
8283
}
8384
Ok(__struct)

mavlink-bindgen/tests/snapshots/[email protected]

Lines changed: 17 additions & 16 deletions
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,6 @@
11
---
22
source: mavlink-bindgen/tests/e2e_snapshots.rs
3+
assertion_line: 26
34
expression: contents
45
---
56
#![doc = "MAVLink parameters dialect."]
@@ -116,8 +117,8 @@ impl MessageData for PARAM_REQUEST_LIST_DATA {
116117
Bytes::new(__input)
117118
};
118119
let mut __struct = Self::default();
119-
__struct.target_system = buf.get_u8();
120-
__struct.target_component = buf.get_u8();
120+
__struct.target_system = buf.get_u8()?;
121+
__struct.target_component = buf.get_u8()?;
121122
Ok(__struct)
122123
}
123124
fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
@@ -201,12 +202,12 @@ impl MessageData for PARAM_REQUEST_READ_DATA {
201202
Bytes::new(__input)
202203
};
203204
let mut __struct = Self::default();
204-
__struct.param_index = buf.get_i16_le();
205-
__struct.target_system = buf.get_u8();
206-
__struct.target_component = buf.get_u8();
205+
__struct.param_index = buf.get_i16_le()?;
206+
__struct.target_system = buf.get_u8()?;
207+
__struct.target_component = buf.get_u8()?;
207208
let mut tmp = [0_u8; 16usize];
208209
for v in &mut tmp {
209-
*v = buf.get_u8();
210+
*v = buf.get_u8()?;
210211
}
211212
__struct.param_id = CharArray::new(tmp);
212213
Ok(__struct)
@@ -299,15 +300,15 @@ impl MessageData for PARAM_SET_DATA {
299300
Bytes::new(__input)
300301
};
301302
let mut __struct = Self::default();
302-
__struct.param_value = buf.get_f32_le();
303-
__struct.target_system = buf.get_u8();
304-
__struct.target_component = buf.get_u8();
303+
__struct.param_value = buf.get_f32_le()?;
304+
__struct.target_system = buf.get_u8()?;
305+
__struct.target_component = buf.get_u8()?;
305306
let mut tmp = [0_u8; 16usize];
306307
for v in &mut tmp {
307-
*v = buf.get_u8();
308+
*v = buf.get_u8()?;
308309
}
309310
__struct.param_id = CharArray::new(tmp);
310-
let tmp = buf.get_u8();
311+
let tmp = buf.get_u8()?;
311312
__struct.param_type =
312313
FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
313314
enum_type: "MavParamType",
@@ -404,15 +405,15 @@ impl MessageData for PARAM_VALUE_DATA {
404405
Bytes::new(__input)
405406
};
406407
let mut __struct = Self::default();
407-
__struct.param_value = buf.get_f32_le();
408-
__struct.param_count = buf.get_u16_le();
409-
__struct.param_index = buf.get_u16_le();
408+
__struct.param_value = buf.get_f32_le()?;
409+
__struct.param_count = buf.get_u16_le()?;
410+
__struct.param_index = buf.get_u16_le()?;
410411
let mut tmp = [0_u8; 16usize];
411412
for v in &mut tmp {
412-
*v = buf.get_u8();
413+
*v = buf.get_u8()?;
413414
}
414415
__struct.param_id = CharArray::new(tmp);
415-
let tmp = buf.get_u8();
416+
let tmp = buf.get_u8()?;
416417
__struct.param_type =
417418
FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
418419
enum_type: "MavParamType",

0 commit comments

Comments
 (0)