From 1b6ec1d5ad33567e0bc62a2a1f6a5bb2b68fe31b Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 6 Sep 2018 11:56:23 +1000 Subject: [PATCH] AP_AccelCal: use mavlink define for field length Also remove special-case handling for carriage return; no user of this function has this problem. --- libraries/AP_AccelCal/AP_AccelCal.cpp | 7 ++----- 1 file changed, 2 insertions(+), 5 deletions(-) diff --git a/libraries/AP_AccelCal/AP_AccelCal.cpp b/libraries/AP_AccelCal/AP_AccelCal.cpp index 226ffe53e3..f74a67e430 100644 --- a/libraries/AP_AccelCal/AP_AccelCal.cpp +++ b/libraries/AP_AccelCal/AP_AccelCal.cpp @@ -381,15 +381,12 @@ void AP_AccelCal::_printf(const char* fmt, ...) if (!_gcs) { return; } - char msg[50]; + char msg[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1]; va_list ap; va_start(ap, fmt); hal.util->vsnprintf(msg, sizeof(msg), fmt, ap); va_end(ap); - if (msg[strlen(msg)-1] == '\n') { - // STATUSTEXT messages should not add linefeed - msg[strlen(msg)-1] = 0; - } + AP_HAL::UARTDriver *uart = _gcs->get_uart(); /* * to ensure these messages get to the user we need to wait for the