From ce3de6b04779e305885db6f25b58ceb382ef2ae3 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Mon, 28 Jan 2019 19:06:50 +0900 Subject: [PATCH] Rover: send_wheel_encoder_distance uses definition for array size --- APMrover2/GCS_Mavlink.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/APMrover2/GCS_Mavlink.cpp b/APMrover2/GCS_Mavlink.cpp index 7064657473..59888ae05e 100644 --- a/APMrover2/GCS_Mavlink.cpp +++ b/APMrover2/GCS_Mavlink.cpp @@ -291,7 +291,7 @@ void Rover::send_wheel_encoder_distance(mavlink_channel_t chan) { // send wheel encoder data using wheel_distance message if (g2.wheel_encoder.num_sensors() > 0) { - double distances[16] {}; + double distances[MAVLINK_MSG_WHEEL_DISTANCE_FIELD_DISTANCE_LEN] {}; for (uint8_t i = 0; i < g2.wheel_encoder.num_sensors(); i++) { distances[i] = wheel_encoder_last_distance_m[i]; }