From e797d69cb724f8fb246c53729f7d87a012676edb Mon Sep 17 00:00:00 2001 From: Mark K Cowan Date: Fri, 24 Nov 2017 18:38:32 +0000 Subject: [PATCH] Fixed failing build when socket.h adds flexible arrays to end of structures. --- .../linux/include/uavcan_linux/socketcan.hpp | 15 +++++++-------- 1 file changed, 7 insertions(+), 8 deletions(-) diff --git a/libuavcan_drivers/linux/include/uavcan_linux/socketcan.hpp b/libuavcan_drivers/linux/include/uavcan_linux/socketcan.hpp index d56980bcc6..a9f645949d 100644 --- a/libuavcan_drivers/linux/include/uavcan_linux/socketcan.hpp +++ b/libuavcan_drivers/linux/include/uavcan_linux/socketcan.hpp @@ -219,18 +219,17 @@ class SocketCanIface : public uavcan::ICanIface iov.iov_base = &sockcan_frame; iov.iov_len = sizeof(sockcan_frame); - struct Control - { - cmsghdr cm; - std::uint8_t data[sizeof(::timeval)]; - }; - auto control = Control(); + static constexpr size_t ControlSize = sizeof(cmsghdr) + sizeof(::timeval); + using ControlStorage = typename std::aligned_storage::type; + ControlStorage control_storage; + auto control = reinterpret_cast(&control_storage); + std::fill(control, control + ControlSize, 0x00); auto msg = ::msghdr(); msg.msg_iov = &iov; msg.msg_iovlen = 1; - msg.msg_control = &control; - msg.msg_controllen = sizeof(control); + msg.msg_control = control; + msg.msg_controllen = ControlSize; const int res = ::recvmsg(fd_, &msg, MSG_DONTWAIT); if (res <= 0)