mirror of https://github.com/ArduPilot/ardupilot
AP_Logger: fixed string warnings
This commit is contained in:
parent
8b95fac214
commit
930726ca9a
|
@ -319,14 +319,14 @@ bool AP_Logger::labels_string_is_good(const char *labels) const
|
||||||
// label_offsets.
|
// label_offsets.
|
||||||
char *label_offsets[LS_LABELS_SIZE];
|
char *label_offsets[LS_LABELS_SIZE];
|
||||||
uint8_t label_offsets_offset = 0;
|
uint8_t label_offsets_offset = 0;
|
||||||
char labels_copy[LS_LABELS_SIZE];
|
char labels_copy[LS_LABELS_SIZE+1] {};
|
||||||
strncpy(labels_copy, labels, ARRAY_SIZE(labels_copy));
|
strncpy(labels_copy, labels, LS_LABELS_SIZE);
|
||||||
if (labels_copy[0] == ',') {
|
if (labels_copy[0] == ',') {
|
||||||
Debug("Leading comma in (%s)", labels);
|
Debug("Leading comma in (%s)", labels);
|
||||||
passed = false;
|
passed = false;
|
||||||
}
|
}
|
||||||
label_offsets[label_offsets_offset++] = labels_copy;
|
label_offsets[label_offsets_offset++] = labels_copy;
|
||||||
const uint8_t len = strnlen(labels_copy, ARRAY_SIZE(labels_copy));
|
const uint8_t len = strnlen(labels_copy, LS_LABELS_SIZE);
|
||||||
for (uint8_t i=0; i<len; i++) {
|
for (uint8_t i=0; i<len; i++) {
|
||||||
if (labels_copy[i] == ',') {
|
if (labels_copy[i] == ',') {
|
||||||
if (labels_copy[i+1] == '\0') {
|
if (labels_copy[i+1] == '\0') {
|
||||||
|
|
Loading…
Reference in New Issue