Fix buffer alignment issues on ESP32 and ARM platforms
Summary
This PR fixes buffer alignment issues that cause MAVLink message corruption on ESP32 (Xtensa) and ARM platforms.
Problem
ESP32 and ARM processors require proper memory alignment when accessing multi-byte values (float, int32, etc.) through char buffers. Without proper alignment, these platforms can experience:
- Data corruption when reading/writing values
- Stack corruption leading to incorrect message lengths
- ATTITUDE messages reporting 385 bytes instead of 28 bytes
Solution
- Added
MAVLINK_ALIGNED_BUFmacro that usesalignas(4)for ESP32/ARM platforms - Updated code generator to use
MAVLINK_ALIGNED_BUFinstead of plainchar[]arrays - Included
stdalign.hwhen alignment is needed
Changes
- generator/C/include_v2.0/protocol.h: Added MAVLINK_ALIGNED_BUF macro definition
- generator/mavgen_c.py: Updated all buffer declarations to use the new macro
Testing
- Tested on ESP32-S3 hardware where the issue was originally observed
- Verified MAVLink messages are now correctly sized and uncorrupted
- No impact on other platforms (macro defaults to plain char[] on non-ARM/ESP32)
Related Issues
This resolves MAVLink corruption issues observed in ArduPilot on ESP32 platforms.
@Bwooce thanks for raising this - what is surprising is arm (specifically STM32) is the most widely used platform that MAVLink is used on. So why are we not seeing issues in current usage? I think that for MAVLINK_NEED_BYTE_SWAP or !MAVLINK_ALIGNED_FIELDS it should be mapping the _mav_put_XXX() functions onto byte_copy_YY() which maps to a function that copies byte by byte. We could use what you've done and then potentially make things a bit more efficient by avoiding the byte by byte copies