Browse Source

AP_AccelCal: use mavlink define for field length

Also remove special-case handling for carriage return; no user of this
function has this problem.
mission-4.1.18
Peter Barker 7 years ago committed by Andrew Tridgell
parent
commit
1b6ec1d5ad
  1. 7
      libraries/AP_AccelCal/AP_AccelCal.cpp

7
libraries/AP_AccelCal/AP_AccelCal.cpp

@ -381,15 +381,12 @@ void AP_AccelCal::_printf(const char* fmt, ...) @@ -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

Loading…
Cancel
Save