GCS_MAVLink: adjust for min_length mavlink2 API change

This commit is contained in:
Andrew Tridgell 2016-04-06 19:30:03 +10:00
parent 318ec69465
commit 048fc8d39e
3 changed files with 6 additions and 1 deletions

View File

@ -308,6 +308,7 @@ void GCS_MAVLINK::handle_mission_request(AP_Mission &mission, mavlink_message_t
_mav_finalize_message_chan_send(chan,
MAVLINK_MSG_ID_MISSION_ITEM_INT,
(const char *)&ret_packet,
MAVLINK_MSG_ID_MISSION_ITEM_MIN_LEN,
MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN,
MAVLINK_MSG_ID_MISSION_ITEM_INT_CRC);
} else {
@ -349,6 +350,7 @@ void GCS_MAVLINK::handle_mission_request(AP_Mission &mission, mavlink_message_t
_mav_finalize_message_chan_send(chan,
MAVLINK_MSG_ID_MISSION_ITEM,
(const char *)&ret_packet,
MAVLINK_MSG_ID_MISSION_ITEM_MIN_LEN,
MAVLINK_MSG_ID_MISSION_ITEM_LEN,
MAVLINK_MSG_ID_MISSION_ITEM_CRC);
}

View File

@ -238,7 +238,9 @@ bool GCS_MAVLINK::handle_log_send_data(DataFlash_Class &dataflash)
packet.id = _log_num_data;
packet.count = ret;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_DATA, (const char *)&packet,
MAVLINK_MSG_ID_LOG_DATA_LEN, MAVLINK_MSG_ID_LOG_DATA_CRC);
MAVLINK_MSG_ID_LOG_DATA_MIN_LEN,
MAVLINK_MSG_ID_LOG_DATA_LEN,
MAVLINK_MSG_ID_LOG_DATA_CRC);
_log_data_offset += len;
_log_data_remaining -= len;

View File

@ -154,6 +154,7 @@ more_data:
_mav_finalize_message_chan_send(chan,
MAVLINK_MSG_ID_SERIAL_CONTROL,
(const char *)&packet,
MAVLINK_MSG_ID_SERIAL_CONTROL_MIN_LEN,
MAVLINK_MSG_ID_SERIAL_CONTROL_LEN,
MAVLINK_MSG_ID_SERIAL_CONTROL_CRC);
if ((flags & SERIAL_CONTROL_FLAG_MULTI) && packet.count != 0) {