mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-23 09:08:30 -04:00
GCS_MAVLink: adjust for min_length mavlink2 API change
This commit is contained in:
parent
318ec69465
commit
048fc8d39e
@ -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);
|
||||
}
|
||||
|
@ -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;
|
||||
|
@ -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) {
|
||||
|
Loading…
Reference in New Issue
Block a user