Ignore warnings about access to packed struct in MAVlink as the accessed member is actually aligned.
This commit is contained in:
parent
8cff785c70
commit
52a66a24f9
|
@ -81,9 +81,18 @@ MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, ui
|
||||||
msg->seq = mavlink_get_channel_status(chan)->current_tx_seq;
|
msg->seq = mavlink_get_channel_status(chan)->current_tx_seq;
|
||||||
mavlink_get_channel_status(chan)->current_tx_seq = mavlink_get_channel_status(chan)->current_tx_seq+1;
|
mavlink_get_channel_status(chan)->current_tx_seq = mavlink_get_channel_status(chan)->current_tx_seq+1;
|
||||||
msg->checksum = crc_calculate(((const uint8_t*)(msg)) + 3, MAVLINK_CORE_HEADER_LEN);
|
msg->checksum = crc_calculate(((const uint8_t*)(msg)) + 3, MAVLINK_CORE_HEADER_LEN);
|
||||||
|
// msg->checksum is actually aligned
|
||||||
|
#pragma GCC diagnostic push
|
||||||
|
#pragma GCC diagnostic ignored "-Waddress-of-packed-member"
|
||||||
crc_accumulate_buffer(&msg->checksum, _MAV_PAYLOAD(msg), msg->len);
|
crc_accumulate_buffer(&msg->checksum, _MAV_PAYLOAD(msg), msg->len);
|
||||||
|
#pragma GCC diagnostic pop
|
||||||
|
|
||||||
#if MAVLINK_CRC_EXTRA
|
#if MAVLINK_CRC_EXTRA
|
||||||
|
// msg->checksum is actually aligned
|
||||||
|
#pragma GCC diagnostic push
|
||||||
|
#pragma GCC diagnostic ignored "-Waddress-of-packed-member"
|
||||||
crc_accumulate(crc_extra, &msg->checksum);
|
crc_accumulate(crc_extra, &msg->checksum);
|
||||||
|
#pragma GCC diagnostic pop
|
||||||
#endif
|
#endif
|
||||||
mavlink_ck_a(msg) = (uint8_t)(msg->checksum & 0xFF);
|
mavlink_ck_a(msg) = (uint8_t)(msg->checksum & 0xFF);
|
||||||
mavlink_ck_b(msg) = (uint8_t)(msg->checksum >> 8);
|
mavlink_ck_b(msg) = (uint8_t)(msg->checksum >> 8);
|
||||||
|
@ -195,12 +204,20 @@ union __mavlink_bitfield {
|
||||||
|
|
||||||
MAVLINK_HELPER void mavlink_start_checksum(mavlink_message_t* msg)
|
MAVLINK_HELPER void mavlink_start_checksum(mavlink_message_t* msg)
|
||||||
{
|
{
|
||||||
|
// msg->checksum is actually aligned
|
||||||
|
#pragma GCC diagnostic push
|
||||||
|
#pragma GCC diagnostic ignored "-Waddress-of-packed-member"
|
||||||
crc_init(&msg->checksum);
|
crc_init(&msg->checksum);
|
||||||
|
#pragma GCC diagnostic pop
|
||||||
}
|
}
|
||||||
|
|
||||||
MAVLINK_HELPER void mavlink_update_checksum(mavlink_message_t* msg, uint8_t c)
|
MAVLINK_HELPER void mavlink_update_checksum(mavlink_message_t* msg, uint8_t c)
|
||||||
{
|
{
|
||||||
|
// msg->checksum is actually aligned
|
||||||
|
#pragma GCC diagnostic push
|
||||||
|
#pragma GCC diagnostic ignored "-Waddress-of-packed-member"
|
||||||
crc_accumulate(c, &msg->checksum);
|
crc_accumulate(c, &msg->checksum);
|
||||||
|
#pragma GCC diagnostic pop
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
|
|
Loading…
Reference in New Issue