mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-03 12:14:10 -04:00
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:
parent
902bd7dda6
commit
1b6ec1d5ad
@ -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…
Reference in New Issue
Block a user