AP_Hott_Telem: avoid 1-byte overwrite in prearm check string

In file included from /usr/include/string.h:494:0,
                 from ../../libraries/AP_HAL/AP_HAL_Namespace.h:3,
                 from ../../libraries/AP_HAL/AP_HAL.h:5,
                 from ../../libraries/AP_Hott_Telem/AP_Hott_Telem.h:17,
                 from ../../libraries/AP_Hott_Telem/AP_Hott_Telem.cpp:23:
In function ‘char* strncpy(char*, const char*, size_t)’,
    inlined from ‘void AP_Hott_Telem::send_Vario()’ at ../../libraries/AP_Hott_Telem/AP_Hott_Telem.cpp:366:20:
/usr/include/x86_64-linux-gnu/bits/string_fortified.h:106:71: warning: ‘char* __builtin___strncpy_chk(char*, const char*, long unsigned int, long unsigned int)’: specified bound 8 exceeds the size 7 of the destination [-Wstringop-overflow=]
   return __builtin___strncpy_chk (__dest, __src, __len, __bos (__dest));
                                                                       ^
In function ‘char* strncpy(char*, const char*, size_t)’,
    inlined from ‘void AP_Hott_Telem::send_Vario()’ at ../../libraries/AP_Hott_Telem/AP_Hott_Telem.cpp:368:20:
/usr/include/x86_64-linux-gnu/bits/string_fortified.h:106:71: warning: ‘char* __builtin___strncpy_chk(char*, const char*, long unsigned int, long unsigned int)’: specified bound 8 exceeds the size 7 of the destination [-Wstringop-overflow=]
   return __builtin___strncpy_chk (__dest, __src, __len, __bos (__dest));
This commit is contained in:
Peter Barker 2020-01-28 12:31:57 +11:00 committed by Andrew Tridgell
parent b47181a86f
commit a1f0452940
1 changed files with 2 additions and 5 deletions

View File

@ -362,11 +362,8 @@ void AP_Hott_Telem::send_Vario(void)
}
} else {
strncpy(msg.text[1], "DISARM", sizeof(msg.text[1]));
if (AP_Notify::flags.pre_arm_check) {
strncpy(msg.text[2], "CK:PASS", sizeof(msg.text[2])+1);
} else {
strncpy(msg.text[2], "CK:FAIL", sizeof(msg.text[2])+1);
}
const char *ck = AP_Notify::flags.pre_arm_check ? "CK:PASS" : "CK:FAIL";
memcpy(msg.text[2], ck, MIN(strlen(ck), sizeof(msg.text[2])));
}
send_packet((const uint8_t *)&msg, sizeof(msg));