Browse Source

GCS_MAVLink: adjust for min_length mavlink2 API change

mission-4.1.18
Andrew Tridgell 9 years ago
parent
commit
048fc8d39e
  1. 2
      libraries/GCS_MAVLink/GCS_Common.cpp
  2. 4
      libraries/GCS_MAVLink/GCS_Logs.cpp
  3. 1
      libraries/GCS_MAVLink/GCS_serial_control.cpp

2
libraries/GCS_MAVLink/GCS_Common.cpp

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

4
libraries/GCS_MAVLink/GCS_Logs.cpp

@ -238,7 +238,9 @@ bool GCS_MAVLINK::handle_log_send_data(DataFlash_Class &dataflash)
packet.id = _log_num_data; packet.id = _log_num_data;
packet.count = ret; packet.count = ret;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_DATA, (const char *)&packet, _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_offset += len;
_log_data_remaining -= len; _log_data_remaining -= len;

1
libraries/GCS_MAVLink/GCS_serial_control.cpp

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

Loading…
Cancel
Save