Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Improve final binary size #244

Conversation

G1gg1L3s
Copy link
Contributor

Hi! While playing around with the library, I noticed that the routines for serialising and deserialising messages are compiled to pretty big functions. So, I tried to optimised them a bit for a size, which is handy for embedded devices.

First, I added inline hints to the Bytes struct to push a compiler to optimising these function calls to simple instructions. The <MavlinkMessage>::ser always ensures that the buffer has the correct size, the compiler strips out the length checks and panics in all Bytes methods, reducing the code size.

Second, I added a check for a buffer size in the <MavlinkMessage>::deser method. This hints a compiler that the buffer is always of the correct size, so the subsequent checks in the BytesMut method can also be optimised away. And they are optimised even without the inline hints.

I measured the result using cargo bloat on amd64 architecture. Here is the before result for one of the tests:

$ cargo bloat --release --filter 'mavlink::common' --features common --test  tcp_loopback_tests 2> /dev/null
File .text     Size   Crate Name
0.3%  2.1%  17.4KiB mavlink <mavlink::common::MavMessage as mavlink_core::Message>::parse
0.0%  0.4%   3.0KiB mavlink <mavlink::common::MavMessage as mavlink_core::Message>::ser
0.0%  0.3%   2.4KiB mavlink <mavlink::common::ONBOARD_COMPUTER_STATUS_DATA as mavlink_core::MessageData>::deser
0.0%  0.3%   2.2KiB mavlink <mavlink::common::GIMBAL_DEVICE_INFORMATION_DATA as mavlink_core::MessageData>::deser
0.0%  0.2%   1.8KiB mavlink <mavlink::common::TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA as mavlink_core::MessageData>::deser
0.0%  0.2%   1.8KiB mavlink <mavlink::common::GPS_STATUS_DATA as mavlink_core::MessageData>::deser
0.0%  0.2%   1.8KiB mavlink <mavlink::common::ODOMETRY_DATA as mavlink_core::MessageData>::deser
0.0%  0.2%   1.7KiB mavlink <mavlink::common::LOCAL_POSITION_NED_COV_DATA as mavlink_core::MessageData>::deser
0.0%  0.2%   1.7KiB mavlink <mavlink::common::CELLULAR_CONFIG_DATA as mavlink_core::MessageData>::deser
0.0%  0.2%   1.6KiB mavlink <mavlink::common::SMART_BATTERY_INFO_DATA as mavlink_core::MessageData>::deser
0.0%  0.2%   1.3KiB mavlink mavlink::common::_IMPL_NUM_FromPrimitive_FOR_MavCmd::<impl num_traits::cast::FromPrimitive for mavlink::common::MavCmd>::from_i64
0.0%  0.2%   1.3KiB mavlink <mavlink::common::MavMessage as mavlink_core::Message>::message_id
0.0%  0.2%   1.3KiB mavlink <mavlink::common::GLOBAL_POSITION_INT_COV_DATA as mavlink_core::MessageData>::deser
0.0%  0.2%   1.3KiB mavlink <mavlink::common::GIMBAL_DEVICE_INFORMATION_DATA as mavlink_core::MessageData>::ser
0.0%  0.2%   1.2KiB mavlink <mavlink::common::ONBOARD_COMPUTER_STATUS_DATA as mavlink_core::MessageData>::ser
0.0%  0.1%   1.2KiB mavlink <mavlink::common::CAMERA_INFORMATION_DATA as mavlink_core::MessageData>::deser
0.0%  0.1%   1.2KiB mavlink <mavlink::common::GPS_STATUS_DATA as mavlink_core::MessageData>::ser
0.0%  0.1%   1.1KiB mavlink <mavlink::common::OPEN_DRONE_ID_ARM_STATUS_DATA as mavlink_core::MessageData>::deser
0.0%  0.1%   1.1KiB mavlink <mavlink::common::STATUSTEXT_DATA as mavlink_core::MessageData>::deser
0.0%  0.1%   1.0KiB mavlink <mavlink::common::OPEN_DRONE_ID_LOCATION_DATA as mavlink_core::MessageData>::deser
2.1% 15.8% 129.5KiB         And 399 smaller methods. Use -n N to show more.
2.9% 21.6% 176.8KiB         filtered data size, the file size is 6.0MiB

And here is the result after all optimisations:

$ cargo bloat --release --filter 'mavlink::common' --features common --test  tcp_loopback_tests 2> /dev/null
File .text    Size   Crate Name
0.3%  2.7% 19.3KiB mavlink <mavlink::common::MavMessage as mavlink_core::Message>::parse
0.0%  0.2%  1.7KiB mavlink <mavlink::common::MavMessage as mavlink_core::Message>::ser
0.0%  0.2%  1.3KiB mavlink mavlink::common::_IMPL_NUM_FromPrimitive_FOR_MavCmd::<impl num_traits::cast::FromPrimitive for mavlink::common::MavCmd>::from_i64
0.0%  0.2%  1.3KiB mavlink <mavlink::common::MavMessage as mavlink_core::Message>::message_id
0.0%  0.1%    622B mavlink <mavlink::common::MavMessage as mavlink_core::Message>::extra_crc
0.0%  0.1%    609B mavlink <mavlink::common::DISTANCE_SENSOR_DATA as mavlink_core::MessageData>::deser
0.0%  0.1%    444B mavlink <mavlink::common::ONBOARD_COMPUTER_STATUS_DATA as mavlink_core::MessageData>::deser
0.0%  0.1%    430B mavlink <mavlink::common::ODOMETRY_DATA as mavlink_core::MessageData>::deser
0.0%  0.1%    399B mavlink <mavlink::common::OPEN_DRONE_ID_LOCATION_DATA as mavlink_core::MessageData>::deser
0.0%  0.1%    373B mavlink <mavlink::common::TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA as mavlink_core::MessageData>::deser
0.0%  0.0%    338B mavlink <mavlink::common::TUNNEL_DATA as mavlink_core::MessageData>::deser
0.0%  0.0%    318B mavlink <mavlink::common::SERIAL_CONTROL_DATA as mavlink_core::MessageData>::deser
0.0%  0.0%    312B mavlink <mavlink::common::VIDEO_STREAM_INFORMATION_DATA as mavlink_core::MessageData>::deser
0.0%  0.0%    293B mavlink <mavlink::common::OPEN_DRONE_ID_SYSTEM_DATA as mavlink_core::MessageData>::deser
0.0%  0.0%    286B mavlink <mavlink::common::PARAM_EXT_ACK_DATA as mavlink_core::MessageData>::deser
0.0%  0.0%    286B mavlink <mavlink::common::CAMERA_INFORMATION_DATA as mavlink_core::MessageData>::deser
0.0%  0.0%    278B mavlink <mavlink::common::GLOBAL_POSITION_INT_COV_DATA as mavlink_core::MessageData>::deser
0.0%  0.0%    265B mavlink <mavlink::common::UTM_GLOBAL_POSITION_DATA as mavlink_core::MessageData>::deser
0.0%  0.0%    262B mavlink <mavlink::common::LOCAL_POSITION_NED_COV_DATA as mavlink_core::MessageData>::deser
0.0%  0.0%    261B mavlink <mavlink::common::HIL_CONTROLS_DATA as mavlink_core::MessageData>::deser
0.6%  5.4% 38.1KiB         And 305 smaller methods. Use -n N to show more.
1.1%  9.6% 67.5KiB         filtered data size, the file size is 5.8MiB

I also measured the code size for thumbv7em-none-eabihf on a small STM32 and the effect is much the same, so I'm sure that this will be useful for other targets as well.

The #[inline] ensures that methods are optimised in the `deser`
method. This ensures that all the checks and panics are optimised
away because the deser method ensures that the buffer is always of
correct size. This reduces and simplifies the code substantially.

For example, here is cargo bloat output before:

```
$ cargo bloat --release --filter 'mavlink::common' --features common --test  tcp_loopback_tests 2> /dev/null
File .text     Size   Crate Name
0.3%  2.1%  17.4KiB mavlink <mavlink::common::MavMessage as mavlink_core::Message>::parse
0.0%  0.4%   3.0KiB mavlink <mavlink::common::MavMessage as mavlink_core::Message>::ser
0.0%  0.3%   2.4KiB mavlink <mavlink::common::ONBOARD_COMPUTER_STATUS_DATA as mavlink_core::MessageData>::deser
0.0%  0.3%   2.2KiB mavlink <mavlink::common::GIMBAL_DEVICE_INFORMATION_DATA as mavlink_core::MessageData>::deser
0.0%  0.2%   1.8KiB mavlink <mavlink::common::TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA as mavlink_core::MessageData>::deser
0.0%  0.2%   1.8KiB mavlink <mavlink::common::GPS_STATUS_DATA as mavlink_core::MessageData>::deser
0.0%  0.2%   1.8KiB mavlink <mavlink::common::ODOMETRY_DATA as mavlink_core::MessageData>::deser
0.0%  0.2%   1.7KiB mavlink <mavlink::common::LOCAL_POSITION_NED_COV_DATA as mavlink_core::MessageData>::deser
0.0%  0.2%   1.7KiB mavlink <mavlink::common::CELLULAR_CONFIG_DATA as mavlink_core::MessageData>::deser
0.0%  0.2%   1.6KiB mavlink <mavlink::common::SMART_BATTERY_INFO_DATA as mavlink_core::MessageData>::deser
0.0%  0.2%   1.3KiB mavlink mavlink::common::_IMPL_NUM_FromPrimitive_FOR_MavCmd::<impl num_traits::cast::FromPrimitive for mavlink::common::MavCmd>::from_i64
0.0%  0.2%   1.3KiB mavlink <mavlink::common::MavMessage as mavlink_core::Message>::message_id
0.0%  0.2%   1.3KiB mavlink <mavlink::common::GLOBAL_POSITION_INT_COV_DATA as mavlink_core::MessageData>::deser
0.0%  0.2%   1.3KiB mavlink <mavlink::common::GIMBAL_DEVICE_INFORMATION_DATA as mavlink_core::MessageData>::ser
0.0%  0.2%   1.2KiB mavlink <mavlink::common::ONBOARD_COMPUTER_STATUS_DATA as mavlink_core::MessageData>::ser
0.0%  0.1%   1.2KiB mavlink <mavlink::common::CAMERA_INFORMATION_DATA as mavlink_core::MessageData>::deser
0.0%  0.1%   1.2KiB mavlink <mavlink::common::GPS_STATUS_DATA as mavlink_core::MessageData>::ser
0.0%  0.1%   1.1KiB mavlink <mavlink::common::OPEN_DRONE_ID_ARM_STATUS_DATA as mavlink_core::MessageData>::deser
0.0%  0.1%   1.1KiB mavlink <mavlink::common::STATUSTEXT_DATA as mavlink_core::MessageData>::deser
0.0%  0.1%   1.0KiB mavlink <mavlink::common::OPEN_DRONE_ID_LOCATION_DATA as mavlink_core::MessageData>::deser
2.1% 15.8% 129.5KiB         And 399 smaller methods. Use -n N to show more.
2.9% 21.6% 176.8KiB         filtered data size, the file size is 6.0MiB
```

And here is after:

```
$ cargo bloat --release --filter 'mavlink::common' --features common --test  tcp_loopback_tests 2> /dev/null
File .text     Size   Crate Name
0.3%  2.6%  19.3KiB mavlink <mavlink::common::MavMessage as mavlink_core::Message>::parse
0.1%  0.4%   3.0KiB mavlink <mavlink::common::MavMessage as mavlink_core::Message>::ser
0.0%  0.2%   1.3KiB mavlink mavlink::common::_IMPL_NUM_FromPrimitive_FOR_MavCmd::<impl num_traits::cast::FromPrimitive for mavlink::common::MavCmd>::from_i64
0.0%  0.2%   1.3KiB mavlink <mavlink::common::MavMessage as mavlink_core::Message>::message_id
0.0%  0.2%   1.3KiB mavlink <mavlink::common::GIMBAL_DEVICE_INFORMATION_DATA as mavlink_core::MessageData>::ser
0.0%  0.2%   1.2KiB mavlink <mavlink::common::ONBOARD_COMPUTER_STATUS_DATA as mavlink_core::MessageData>::ser
0.0%  0.2%   1.2KiB mavlink <mavlink::common::GPS_STATUS_DATA as mavlink_core::MessageData>::ser
0.0%  0.1%    1013B mavlink <mavlink::common::CELLULAR_CONFIG_DATA as mavlink_core::MessageData>::ser
0.0%  0.1%     982B mavlink <mavlink::common::CAMERA_INFORMATION_DATA as mavlink_core::MessageData>::ser
0.0%  0.1%     951B mavlink <mavlink::common::TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA as mavlink_core::MessageData>::ser
0.0%  0.1%     937B mavlink <mavlink::common::SMART_BATTERY_INFO_DATA as mavlink_core::MessageData>::ser
0.0%  0.1%     893B mavlink <mavlink::common::ODOMETRY_DATA as mavlink_core::MessageData>::ser
0.0%  0.1%     861B mavlink <mavlink::common::LOCAL_POSITION_NED_COV_DATA as mavlink_core::MessageData>::ser
0.0%  0.1%     692B mavlink <mavlink::common::GLOBAL_POSITION_INT_COV_DATA as mavlink_core::MessageData>::ser
0.0%  0.1%     658B mavlink <mavlink::common::OPEN_DRONE_ID_ARM_STATUS_DATA as mavlink_core::MessageData>::ser
0.0%  0.1%     658B mavlink <mavlink::common::STATUSTEXT_DATA as mavlink_core::MessageData>::ser
0.0%  0.1%     650B mavlink <mavlink::common::OPEN_DRONE_ID_AUTHENTICATION_DATA as mavlink_core::MessageData>::ser
0.0%  0.1%     630B mavlink <mavlink::common::VIDEO_STREAM_INFORMATION_DATA as mavlink_core::MessageData>::ser
0.0%  0.1%     619B mavlink <mavlink::common::MavMessage as mavlink_core::Message>::extra_crc
0.0%  0.1%     613B mavlink <mavlink::common::EVENT_DATA as mavlink_core::MessageData>::ser
1.1%  9.1%  67.8KiB         And 305 smaller methods. Use -n N to show more.
1.8% 14.3% 106.4KiB         filtered data size, the file size is 5.9MiB
```

These results are for the amd64, but they also apply for other
architectures. For example, I tested it with thumbv7em-none-eabihf
on some STM32, and the code is also reduced (though I'm too lazy to
provide the examples).
Do this check for the whole buffer size before serialisation. This
allows a compiler to optimise away subsequent checks in the BytesMut
methods, which reduces the code size because we don't need to handle
that many panic cases anymore.

Here are the cargo bloat results before the change:

```
$ cargo bloat --release --filter 'mavlink::common' --features common --test  tcp_loopback_tests 2> /dev/null
File .text     Size   Crate Name
0.3%  2.6%  19.3KiB mavlink <mavlink::common::MavMessage as mavlink_core::Message>::parse
0.1%  0.4%   3.0KiB mavlink <mavlink::common::MavMessage as mavlink_core::Message>::ser
0.0%  0.2%   1.3KiB mavlink mavlink::common::_IMPL_NUM_FromPrimitive_FOR_MavCmd::<impl num_traits::cast::FromPrimitive for mavlink::common::MavCmd>::from_i64
0.0%  0.2%   1.3KiB mavlink <mavlink::common::MavMessage as mavlink_core::Message>::message_id
0.0%  0.2%   1.3KiB mavlink <mavlink::common::GIMBAL_DEVICE_INFORMATION_DATA as mavlink_core::MessageData>::ser
0.0%  0.2%   1.2KiB mavlink <mavlink::common::ONBOARD_COMPUTER_STATUS_DATA as mavlink_core::MessageData>::ser
0.0%  0.2%   1.2KiB mavlink <mavlink::common::GPS_STATUS_DATA as mavlink_core::MessageData>::ser
0.0%  0.1%    1013B mavlink <mavlink::common::CELLULAR_CONFIG_DATA as mavlink_core::MessageData>::ser
0.0%  0.1%     982B mavlink <mavlink::common::CAMERA_INFORMATION_DATA as mavlink_core::MessageData>::ser
0.0%  0.1%     951B mavlink <mavlink::common::TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA as mavlink_core::MessageData>::ser
0.0%  0.1%     937B mavlink <mavlink::common::SMART_BATTERY_INFO_DATA as mavlink_core::MessageData>::ser
0.0%  0.1%     893B mavlink <mavlink::common::ODOMETRY_DATA as mavlink_core::MessageData>::ser
0.0%  0.1%     861B mavlink <mavlink::common::LOCAL_POSITION_NED_COV_DATA as mavlink_core::MessageData>::ser
0.0%  0.1%     692B mavlink <mavlink::common::GLOBAL_POSITION_INT_COV_DATA as mavlink_core::MessageData>::ser
0.0%  0.1%     658B mavlink <mavlink::common::STATUSTEXT_DATA as mavlink_core::MessageData>::ser
0.0%  0.1%     658B mavlink <mavlink::common::OPEN_DRONE_ID_ARM_STATUS_DATA as mavlink_core::MessageData>::ser
0.0%  0.1%     650B mavlink <mavlink::common::OPEN_DRONE_ID_AUTHENTICATION_DATA as mavlink_core::MessageData>::ser
0.0%  0.1%     630B mavlink <mavlink::common::VIDEO_STREAM_INFORMATION_DATA as mavlink_core::MessageData>::ser
0.0%  0.1%     618B mavlink <mavlink::common::MavMessage as mavlink_core::Message>::extra_crc
0.0%  0.1%     613B mavlink <mavlink::common::EVENT_DATA as mavlink_core::MessageData>::ser
1.1%  9.1%  67.8KiB         And 305 smaller methods. Use -n N to show more.
1.8% 14.3% 106.4KiB         filtered data size, the file size is 5.9MiB
```

And here are the results after:

```
$ cargo bloat --release --filter 'mavlink::common' --features common --test  tcp_loopback_tests 2> /dev/null
File .text    Size   Crate Name
0.3%  2.7% 19.3KiB mavlink <mavlink::common::MavMessage as mavlink_core::Message>::parse
0.0%  0.2%  1.7KiB mavlink <mavlink::common::MavMessage as mavlink_core::Message>::ser
0.0%  0.2%  1.3KiB mavlink mavlink::common::_IMPL_NUM_FromPrimitive_FOR_MavCmd::<impl num_traits::cast::FromPrimitive for mavlink::common::MavCmd>::from_i64
0.0%  0.2%  1.3KiB mavlink <mavlink::common::MavMessage as mavlink_core::Message>::message_id
0.0%  0.1%    622B mavlink <mavlink::common::MavMessage as mavlink_core::Message>::extra_crc
0.0%  0.1%    609B mavlink <mavlink::common::DISTANCE_SENSOR_DATA as mavlink_core::MessageData>::deser
0.0%  0.1%    444B mavlink <mavlink::common::ONBOARD_COMPUTER_STATUS_DATA as mavlink_core::MessageData>::deser
0.0%  0.1%    430B mavlink <mavlink::common::ODOMETRY_DATA as mavlink_core::MessageData>::deser
0.0%  0.1%    399B mavlink <mavlink::common::OPEN_DRONE_ID_LOCATION_DATA as mavlink_core::MessageData>::deser
0.0%  0.1%    373B mavlink <mavlink::common::TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA as mavlink_core::MessageData>::deser
0.0%  0.0%    338B mavlink <mavlink::common::TUNNEL_DATA as mavlink_core::MessageData>::deser
0.0%  0.0%    318B mavlink <mavlink::common::SERIAL_CONTROL_DATA as mavlink_core::MessageData>::deser
0.0%  0.0%    312B mavlink <mavlink::common::VIDEO_STREAM_INFORMATION_DATA as mavlink_core::MessageData>::deser
0.0%  0.0%    293B mavlink <mavlink::common::OPEN_DRONE_ID_SYSTEM_DATA as mavlink_core::MessageData>::deser
0.0%  0.0%    286B mavlink <mavlink::common::PARAM_EXT_ACK_DATA as mavlink_core::MessageData>::deser
0.0%  0.0%    286B mavlink <mavlink::common::CAMERA_INFORMATION_DATA as mavlink_core::MessageData>::deser
0.0%  0.0%    278B mavlink <mavlink::common::GLOBAL_POSITION_INT_COV_DATA as mavlink_core::MessageData>::deser
0.0%  0.0%    265B mavlink <mavlink::common::UTM_GLOBAL_POSITION_DATA as mavlink_core::MessageData>::deser
0.0%  0.0%    262B mavlink <mavlink::common::LOCAL_POSITION_NED_COV_DATA as mavlink_core::MessageData>::deser
0.0%  0.0%    261B mavlink <mavlink::common::HIL_CONTROLS_DATA as mavlink_core::MessageData>::deser
0.6%  5.4% 38.1KiB         And 305 smaller methods. Use -n N to show more.
1.1%  9.6% 67.5KiB         filtered data size, the file size is 5.8MiB
```
@patrickelectric
Copy link
Member

@G1gg1L3s please check CI

Sorry, I confused methods and used the `len` instead of `remaining`.
The len is always 0 at the start, so everything was optimised away
:)

After this change, the code size is actually bigger but I have a
couple of ideas that may lower it.
This time it does affect the code size a bit.

Here are results before any changes to the serialisation:

```
$ cargo bloat --release --filter 'mavlink::common' --features common --test  tcp_loopback_tests 2> /dev/null
File .text     Size   Crate Name
0.3%  2.6%  19.3KiB mavlink <mavlink::common::MavMessage as mavlink_core::Message>::parse
0.1%  0.4%   3.0KiB mavlink <mavlink::common::MavMessage as mavlink_core::Message>::ser
0.0%  0.2%   1.3KiB mavlink mavlink::common::_IMPL_NUM_FromPrimitive_FOR_MavCmd::<impl num_traits::cast::FromPrimitive for mavlink::common::MavCmd>::from_i64
0.0%  0.2%   1.3KiB mavlink <mavlink::common::MavMessage as mavlink_core::Message>::message_id
0.0%  0.2%   1.3KiB mavlink <mavlink::common::GIMBAL_DEVICE_INFORMATION_DATA as mavlink_core::MessageData>::ser
0.0%  0.2%   1.2KiB mavlink <mavlink::common::ONBOARD_COMPUTER_STATUS_DATA as mavlink_core::MessageData>::ser
0.0%  0.2%   1.2KiB mavlink <mavlink::common::GPS_STATUS_DATA as mavlink_core::MessageData>::ser
0.0%  0.1%    1013B mavlink <mavlink::common::CELLULAR_CONFIG_DATA as mavlink_core::MessageData>::ser
0.0%  0.1%     982B mavlink <mavlink::common::CAMERA_INFORMATION_DATA as mavlink_core::MessageData>::ser
0.0%  0.1%     951B mavlink <mavlink::common::TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA as mavlink_core::MessageData>::ser
0.0%  0.1%     937B mavlink <mavlink::common::SMART_BATTERY_INFO_DATA as mavlink_core::MessageData>::ser
0.0%  0.1%     893B mavlink <mavlink::common::ODOMETRY_DATA as mavlink_core::MessageData>::ser
0.0%  0.1%     861B mavlink <mavlink::common::LOCAL_POSITION_NED_COV_DATA as mavlink_core::MessageData>::ser
0.0%  0.1%     692B mavlink <mavlink::common::GLOBAL_POSITION_INT_COV_DATA as mavlink_core::MessageData>::ser
0.0%  0.1%     658B mavlink <mavlink::common::STATUSTEXT_DATA as mavlink_core::MessageData>::ser
0.0%  0.1%     658B mavlink <mavlink::common::OPEN_DRONE_ID_ARM_STATUS_DATA as mavlink_core::MessageData>::ser
0.0%  0.1%     650B mavlink <mavlink::common::OPEN_DRONE_ID_AUTHENTICATION_DATA as mavlink_core::MessageData>::ser
0.0%  0.1%     646B mavlink <mavlink::common::MavMessage as mavlink_core::Message>::extra_crc
0.0%  0.1%     630B mavlink <mavlink::common::VIDEO_STREAM_INFORMATION_DATA as mavlink_core::MessageData>::ser
0.0%  0.1%     613B mavlink <mavlink::common::EVENT_DATA as mavlink_core::MessageData>::ser
1.1%  9.1%  67.8KiB         And 305 smaller methods. Use -n N to show more.
1.8% 14.3% 106.4KiB         filtered data size, the file size is 5.9MiB
```

And here are the results after this and the previous commits:

```
$ cargo bloat --release --filter 'mavlink::common' --features common --test  tcp_loopback_tests 2> /dev/null
File .text    Size   Crate Name
0.3%  2.7% 19.7KiB mavlink <mavlink::common::MavMessage as mavlink_core::Message>::parse
0.1%  0.4%  3.0KiB mavlink <mavlink::common::MavMessage as mavlink_core::Message>::ser
0.0%  0.2%  1.3KiB mavlink mavlink::common::_IMPL_NUM_FromPrimitive_FOR_MavCmd::<impl num_traits::cast::FromPrimitive for mavlink::common::MavCmd>::from_i64
0.0%  0.2%  1.3KiB mavlink <mavlink::common::MavMessage as mavlink_core::Message>::message_id
0.0%  0.1%    741B mavlink <mavlink::common::CAN_FILTER_MODIFY_DATA as mavlink_core::MessageData>::ser
0.0%  0.1%    633B mavlink <mavlink::common::MavMessage as mavlink_core::Message>::extra_crc
0.0%  0.1%    609B mavlink <mavlink::common::DISTANCE_SENSOR_DATA as mavlink_core::MessageData>::deser
0.0%  0.1%    497B mavlink <mavlink::common::GLOBAL_POSITION_INT_COV_DATA as mavlink_core::MessageData>::ser
0.0%  0.1%    466B mavlink <mavlink::common::LOCAL_POSITION_NED_COV_DATA as mavlink_core::MessageData>::ser
0.0%  0.1%    459B mavlink <mavlink::common::OBSTACLE_DISTANCE_DATA as mavlink_core::MessageData>::ser
0.0%  0.1%    444B mavlink <mavlink::common::ONBOARD_COMPUTER_STATUS_DATA as mavlink_core::MessageData>::ser
0.0%  0.1%    444B mavlink <mavlink::common::ONBOARD_COMPUTER_STATUS_DATA as mavlink_core::MessageData>::deser
0.0%  0.1%    421B mavlink <mavlink::common::ODOMETRY_DATA as mavlink_core::MessageData>::deser
0.0%  0.1%    406B mavlink <mavlink::common::GIMBAL_DEVICE_SET_ATTITUDE_DATA as mavlink_core::MessageData>::ser
0.0%  0.1%    399B mavlink <mavlink::common::OPEN_DRONE_ID_LOCATION_DATA as mavlink_core::MessageData>::deser
0.0%  0.1%    388B mavlink <mavlink::common::ODOMETRY_DATA as mavlink_core::MessageData>::ser
0.0%  0.1%    373B mavlink <mavlink::common::TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA as mavlink_core::MessageData>::deser
0.0%  0.0%    363B mavlink <mavlink::common::TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA as mavlink_core::MessageData>::ser
0.0%  0.0%    348B mavlink <mavlink::common::RESOURCE_REQUEST_DATA as mavlink_core::MessageData>::ser
0.0%  0.0%    338B mavlink <mavlink::common::TUNNEL_DATA as mavlink_core::MessageData>::deser
0.9%  7.4% 53.7KiB         And 304 smaller methods. Use -n N to show more.
1.4% 11.9% 86.2KiB         filtered data size, the file size is 5.9MiB
```
As described in the comment, these lints are from the empty messages
which have Self::ENCODED_LEN zero. For now, skip this lint in the
check.

The empty messages are actually forbidden by the mavlink schema [1].
But we generate a couple of empty cubepilot messages because the
cubepilot.xml contains a couple of unclosed fields, like so:

[1]: https://github.com/ArduPilot/pymavlink/blob/d251f7acbe9ce45175615fefdd4f094719ec1120/generator/mavschema.xsd#L305

```xml

    <message id="50001" name="CUBEPILOT_RAW_RC">
      <description>Raw RC Data</description>
      <field type="uint8_t[32]" name="rc_raw"/>
    </message>

    <message id="50003" name="HERELINK_TELEM">
      <description>Herelink Telemetry</description>
      <field type="uint8_t" name="rssi"/>
      <field type="int16_t" name="snr"/>
      <field type="uint32_t" name="rf_freq"/>
      <field type="uint32_t" name="link_bw"/>
      <field type="uint32_t" name="link_rate"/>
      <field type="int16_t" name="cpu_temp"/>
      <field type="int16_t" name="board_temp"/>
    </message>
```

Python xml parser does a decend job at recovering from such cases.
However, our current parser just ignores such fields.
@G1gg1L3s
Copy link
Contributor Author

G1gg1L3s commented Jul 21, 2024

@patrickelectric, sorry, my bad. I used the wrong method and didn't test it locally.

Now it works okay, but the final bloat results are a bit higher:

$ cargo bloat --release --filter 'mavlink::common' --features common --test  tcp_loopback_tests 2> /dev/null
File .text    Size   Crate Name
0.3%  2.7% 19.7KiB mavlink <mavlink::common::MavMessage as mavlink_core::Message>::parse
0.1%  0.4%  3.0KiB mavlink <mavlink::common::MavMessage as mavlink_core::Message>::ser
0.0%  0.2%  1.3KiB mavlink mavlink::common::_IMPL_NUM_FromPrimitive_FOR_MavCmd::<impl num_traits::cast::FromPrimitive for mavlink::common::MavCmd>::from_i64
0.0%  0.2%  1.3KiB mavlink <mavlink::common::MavMessage as mavlink_core::Message>::message_id
0.0%  0.1%    741B mavlink <mavlink::common::CAN_FILTER_MODIFY_DATA as mavlink_core::MessageData>::ser
0.0%  0.1%    633B mavlink <mavlink::common::MavMessage as mavlink_core::Message>::extra_crc
0.0%  0.1%    609B mavlink <mavlink::common::DISTANCE_SENSOR_DATA as mavlink_core::MessageData>::deser
0.0%  0.1%    497B mavlink <mavlink::common::GLOBAL_POSITION_INT_COV_DATA as mavlink_core::MessageData>::ser
0.0%  0.1%    466B mavlink <mavlink::common::LOCAL_POSITION_NED_COV_DATA as mavlink_core::MessageData>::ser
0.0%  0.1%    459B mavlink <mavlink::common::OBSTACLE_DISTANCE_DATA as mavlink_core::MessageData>::ser
0.0%  0.1%    444B mavlink <mavlink::common::ONBOARD_COMPUTER_STATUS_DATA as mavlink_core::MessageData>::ser
0.0%  0.1%    444B mavlink <mavlink::common::ONBOARD_COMPUTER_STATUS_DATA as mavlink_core::MessageData>::deser
0.0%  0.1%    421B mavlink <mavlink::common::ODOMETRY_DATA as mavlink_core::MessageData>::deser
0.0%  0.1%    406B mavlink <mavlink::common::GIMBAL_DEVICE_SET_ATTITUDE_DATA as mavlink_core::MessageData>::ser
0.0%  0.1%    399B mavlink <mavlink::common::OPEN_DRONE_ID_LOCATION_DATA as mavlink_core::MessageData>::deser
0.0%  0.1%    388B mavlink <mavlink::common::ODOMETRY_DATA as mavlink_core::MessageData>::ser
0.0%  0.1%    373B mavlink <mavlink::common::TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA as mavlink_core::MessageData>::deser
0.0%  0.0%    363B mavlink <mavlink::common::TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA as mavlink_core::MessageData>::ser
0.0%  0.0%    348B mavlink <mavlink::common::RESOURCE_REQUEST_DATA as mavlink_core::MessageData>::ser
0.0%  0.0%    338B mavlink <mavlink::common::TUNNEL_DATA as mavlink_core::MessageData>::deser
0.9%  7.4% 53.7KiB         And 304 smaller methods. Use -n N to show more.
1.4% 11.9% 86.2KiB         filtered data size, the file size is 5.9MiB

Also, the clippy errors were interesting. It turned out that some messages were generated as empty structs. Particularly - the HERELINK_TELEM and CUBEPILOT_RAW_RC from the cubepilot.xml. This is because they have invalid xml because the field elements are unclosed. The current parser is built in a way that just ignores such fields so the final messages are empty.

For now, I just allowed the warnings in the function. But this should probably be fixed in both parser and the definition. Though I'm not sure how to correctly design such recovery in the parser, maybe just being strict and returning an error is more appropriate way.

@patrickelectric patrickelectric changed the title Optimise serialisation and deserialisation for size Improve final binary size Jul 21, 2024
@patrickelectric patrickelectric merged commit ab925ad into mavlink:master Jul 21, 2024
26 checks passed
@G1gg1L3s G1gg1L3s deleted the optimise-serialisation-and-deserialisation-for-size branch July 22, 2024 06:47
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

2 participants