AP_AccelCal: use mavlink define for field length

Also remove special-case handling for carriage return; no user of this
function has this problem.
This commit is contained in:
Peter Barker 2018-09-06 11:56:23 +10:00 committed by Andrew Tridgell
parent 902bd7dda6
commit 1b6ec1d5ad

View File

@ -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