GCS_MAVLink: fixed assumption on return of snprintf

This commit is contained in:
Andrew Tridgell 2019-09-11 17:44:29 +10:00
parent 412bf24b9a
commit 98c2606c0a

View File

@ -2631,6 +2631,7 @@ void GCS_MAVLINK::handle_statustext(const mavlink_message_t &msg)
"SRC=%u/%u:",
msg.sysid,
msg.compid);
offset = MIN(offset, max_prefix_len);
}
memcpy(&text[offset], packet.text, MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN);