diff --git a/lib/main/MAVLink/mavlink_helpers.h b/lib/main/MAVLink/mavlink_helpers.h index 1f97af631..7cfbc0be4 100644 --- a/lib/main/MAVLink/mavlink_helpers.h +++ b/lib/main/MAVLink/mavlink_helpers.h @@ -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; 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 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); +#pragma GCC diagnostic pop + #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); +#pragma GCC diagnostic pop #endif mavlink_ck_a(msg) = (uint8_t)(msg->checksum & 0xFF); 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) { +// msg->checksum is actually aligned +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Waddress-of-packed-member" crc_init(&msg->checksum); +#pragma GCC diagnostic pop } 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); +#pragma GCC diagnostic pop } /**