From 27702a060bc2523878e9e8a5d03d0a0a6c96732a Mon Sep 17 00:00:00 2001 From: "Dr.-Ing. Amilcar Do Carmo Lucas" Date: Tue, 9 Jan 2018 22:38:14 +0100 Subject: [PATCH] GCS_MAVLink: do not use hardcoded array sizes --- libraries/GCS_MAVLink/GCS_Common.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index f863100ee5..d8f56d6c35 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -1377,13 +1377,13 @@ void GCS_MAVLINK::send_autopilot_version() const uint32_t middleware_sw_version = 0; uint32_t os_sw_version = 0; uint32_t board_version = 0; - char flight_custom_version[8]{}; - char middleware_custom_version[8]{}; - char os_custom_version[8]{}; + char flight_custom_version[MAVLINK_MSG_AUTOPILOT_VERSION_FIELD_FLIGHT_CUSTOM_VERSION_LEN]{}; + char middleware_custom_version[MAVLINK_MSG_AUTOPILOT_VERSION_FIELD_MIDDLEWARE_CUSTOM_VERSION_LEN]{}; + char os_custom_version[MAVLINK_MSG_AUTOPILOT_VERSION_FIELD_OS_CUSTOM_VERSION_LEN]{}; uint16_t vendor_id = 0; uint16_t product_id = 0; uint64_t uid = 0; - uint8_t uid2[18] = {0}; + uint8_t uid2[MAVLINK_MSG_AUTOPILOT_VERSION_FIELD_UID2_LEN] = {0}; const AP_FWVersion &version = get_fwver(); flight_sw_version = version.major << (8 * 3) | \