diff --git a/libraries/AP_RCTelemetry/AP_RCTelemetry.cpp b/libraries/AP_RCTelemetry/AP_RCTelemetry.cpp index 2316ab7794..f0fb270300 100644 --- a/libraries/AP_RCTelemetry/AP_RCTelemetry.cpp +++ b/libraries/AP_RCTelemetry/AP_RCTelemetry.cpp @@ -147,7 +147,7 @@ void AP_RCTelemetry::queue_message(MAV_SEVERITY severity, const char *text) mavlink_statustext_t statustext{}; statustext.severity = severity; - strncpy(statustext.text, text, sizeof(statustext.text)); + strncpy_noterm(statustext.text, text, sizeof(statustext.text)); // The force push will ensure comm links do not block other comm links forever if they fail. // If we push to a full buffer then we overwrite the oldest entry, effectively removing the