mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_HAL_Linux: fix build error with flexible array
Apparently this code came in part from libuavcan that defines this struct Control. They also had the same issue detailed on https://github.com/UAVCAN/libuavcan/issues/116. The solution here is much simpler though: stick to the design of cmsg() even if it's C. As per cmsg(3), use a union together with CMSG_SPACE().
This commit is contained in:
parent
96ae9cef14
commit
cf3a9cddc8
@ -371,18 +371,16 @@ int CAN::_read(uavcan::CanFrame& frame, uavcan::UtcTime& ts_utc, bool& loopback)
|
||||
auto sockcan_frame = can_frame();
|
||||
iov.iov_base = &sockcan_frame;
|
||||
iov.iov_len = sizeof(sockcan_frame);
|
||||
|
||||
struct Control
|
||||
{
|
||||
cmsghdr cm;
|
||||
std::uint8_t data[sizeof(::timeval)];
|
||||
union {
|
||||
uint8_t data[CMSG_SPACE(sizeof(::timeval))];
|
||||
struct cmsghdr align;
|
||||
} control;
|
||||
|
||||
auto msg = msghdr();
|
||||
msg.msg_iov = &iov;
|
||||
msg.msg_iovlen = 1;
|
||||
msg.msg_control = &control;
|
||||
msg.msg_controllen = sizeof(control);
|
||||
msg.msg_control = control.data;
|
||||
msg.msg_controllen = sizeof(control.data);
|
||||
|
||||
const int res = recvmsg(_fd, &msg, MSG_DONTWAIT);
|
||||
if (res <= 0) {
|
||||
|
Loading…
Reference in New Issue
Block a user