mirror of https://github.com/ArduPilot/ardupilot
AP_RCTelemetry: use strncpy_noterm
This commit is contained in:
parent
f80ca85428
commit
7e41874d8f
|
@ -147,7 +147,7 @@ void AP_RCTelemetry::queue_message(MAV_SEVERITY severity, const char *text)
|
||||||
mavlink_statustext_t statustext{};
|
mavlink_statustext_t statustext{};
|
||||||
|
|
||||||
statustext.severity = severity;
|
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.
|
// 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
|
// If we push to a full buffer then we overwrite the oldest entry, effectively removing the
|
||||||
|
|
Loading…
Reference in New Issue