Skip to content

Commit 68b768a

Browse files
authored
Avoid oversized payload parsing buffer allocation when not required (#488)
* avoid oversized payload parsing buffer allocation when not required * adjust snapshot tests
1 parent b339f96 commit 68b768a

7 files changed

Lines changed: 20 additions & 10 deletions

mavlink-bindgen/src/parser.rs

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -953,9 +953,10 @@ impl MavMessage {
953953
quote! {
954954
let avail_len = __input.len();
955955

956-
let mut payload_buf = [0; Self::ENCODED_LEN];
956+
let mut payload_buf;
957957
let mut buf = if avail_len < Self::ENCODED_LEN {
958958
//copy available bytes into an oversized buffer filled with zeros
959+
payload_buf = [0; Self::ENCODED_LEN];
959960
payload_buf[0..avail_len].copy_from_slice(__input);
960961
Bytes::new(&payload_buf)
961962
} else {

mavlink-bindgen/tests/snapshots/e2e_snapshots__deprecated.xml@deprecated.rs.snap

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -117,8 +117,9 @@ impl MessageData for PING_DATA {
117117
__input: &[u8],
118118
) -> Result<Self, ::mavlink_core::error::ParserError> {
119119
let avail_len = __input.len();
120-
let mut payload_buf = [0; Self::ENCODED_LEN];
120+
let mut payload_buf;
121121
let mut buf = if avail_len < Self::ENCODED_LEN {
122+
payload_buf = [0; Self::ENCODED_LEN];
122123
payload_buf[0..avail_len].copy_from_slice(__input);
123124
Bytes::new(&payload_buf)
124125
} else {

mavlink-bindgen/tests/snapshots/e2e_snapshots__heartbeat.xml@heartbeat.rs.snap

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -81,8 +81,9 @@ impl MessageData for HEARTBEAT_DATA {
8181
__input: &[u8],
8282
) -> Result<Self, ::mavlink_core::error::ParserError> {
8383
let avail_len = __input.len();
84-
let mut payload_buf = [0; Self::ENCODED_LEN];
84+
let mut payload_buf;
8585
let mut buf = if avail_len < Self::ENCODED_LEN {
86+
payload_buf = [0; Self::ENCODED_LEN];
8687
payload_buf[0..avail_len].copy_from_slice(__input);
8788
Bytes::new(&payload_buf)
8889
} else {

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

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -81,8 +81,9 @@ impl MessageData for BOOL_TEST_MESSAGE_DATA {
8181
__input: &[u8],
8282
) -> Result<Self, ::mavlink_core::error::ParserError> {
8383
let avail_len = __input.len();
84-
let mut payload_buf = [0; Self::ENCODED_LEN];
84+
let mut payload_buf;
8585
let mut buf = if avail_len < Self::ENCODED_LEN {
86+
payload_buf = [0; Self::ENCODED_LEN];
8687
payload_buf[0..avail_len].copy_from_slice(__input);
8788
Bytes::new(&payload_buf)
8889
} else {

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
@@ -67,8 +67,9 @@ impl MessageData for CUBEPILOT_RAW_RC_DATA {
6767
__input: &[u8],
6868
) -> Result<Self, ::mavlink_core::error::ParserError> {
6969
let avail_len = __input.len();
70-
let mut payload_buf = [0; Self::ENCODED_LEN];
70+
let mut payload_buf;
7171
let mut buf = if avail_len < Self::ENCODED_LEN {
72+
payload_buf = [0; Self::ENCODED_LEN];
7273
payload_buf[0..avail_len].copy_from_slice(__input);
7374
Bytes::new(&payload_buf)
7475
} else {

mavlink-bindgen/tests/snapshots/e2e_snapshots__parameters.xml@parameters.rs.snap

Lines changed: 8 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -107,8 +107,9 @@ impl MessageData for PARAM_REQUEST_LIST_DATA {
107107
__input: &[u8],
108108
) -> Result<Self, ::mavlink_core::error::ParserError> {
109109
let avail_len = __input.len();
110-
let mut payload_buf = [0; Self::ENCODED_LEN];
110+
let mut payload_buf;
111111
let mut buf = if avail_len < Self::ENCODED_LEN {
112+
payload_buf = [0; Self::ENCODED_LEN];
112113
payload_buf[0..avail_len].copy_from_slice(__input);
113114
Bytes::new(&payload_buf)
114115
} else {
@@ -190,8 +191,9 @@ impl MessageData for PARAM_REQUEST_READ_DATA {
190191
__input: &[u8],
191192
) -> Result<Self, ::mavlink_core::error::ParserError> {
192193
let avail_len = __input.len();
193-
let mut payload_buf = [0; Self::ENCODED_LEN];
194+
let mut payload_buf;
194195
let mut buf = if avail_len < Self::ENCODED_LEN {
196+
payload_buf = [0; Self::ENCODED_LEN];
195197
payload_buf[0..avail_len].copy_from_slice(__input);
196198
Bytes::new(&payload_buf)
197199
} else {
@@ -286,8 +288,9 @@ impl MessageData for PARAM_SET_DATA {
286288
__input: &[u8],
287289
) -> Result<Self, ::mavlink_core::error::ParserError> {
288290
let avail_len = __input.len();
289-
let mut payload_buf = [0; Self::ENCODED_LEN];
291+
let mut payload_buf;
290292
let mut buf = if avail_len < Self::ENCODED_LEN {
293+
payload_buf = [0; Self::ENCODED_LEN];
291294
payload_buf[0..avail_len].copy_from_slice(__input);
292295
Bytes::new(&payload_buf)
293296
} else {
@@ -389,8 +392,9 @@ impl MessageData for PARAM_VALUE_DATA {
389392
__input: &[u8],
390393
) -> Result<Self, ::mavlink_core::error::ParserError> {
391394
let avail_len = __input.len();
392-
let mut payload_buf = [0; Self::ENCODED_LEN];
395+
let mut payload_buf;
393396
let mut buf = if avail_len < Self::ENCODED_LEN {
397+
payload_buf = [0; Self::ENCODED_LEN];
394398
payload_buf[0..avail_len].copy_from_slice(__input);
395399
Bytes::new(&payload_buf)
396400
} else {

mavlink-bindgen/tests/snapshots/e2e_snapshots__superseded.xml@superseded.rs.snap

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -152,8 +152,9 @@ impl MessageData for SMART_BATTERY_INFO_DATA {
152152
__input: &[u8],
153153
) -> Result<Self, ::mavlink_core::error::ParserError> {
154154
let avail_len = __input.len();
155-
let mut payload_buf = [0; Self::ENCODED_LEN];
155+
let mut payload_buf;
156156
let mut buf = if avail_len < Self::ENCODED_LEN {
157+
payload_buf = [0; Self::ENCODED_LEN];
157158
payload_buf[0..avail_len].copy_from_slice(__input);
158159
Bytes::new(&payload_buf)
159160
} else {

0 commit comments

Comments
 (0)