AP_Filesystem: crc32: Ensure checksum value is initialized

This commit is contained in:
Iampete1 2024-02-14 11:16:31 +00:00 committed by Randy Mackay
parent 431ef6b4ba
commit 312061b76c
1 changed files with 3 additions and 0 deletions

View File

@ -290,6 +290,9 @@ bool AP_Filesystem::fgets(char *buf, uint8_t buflen, int fd)
// run crc32 over file with given name, returns true if successful // run crc32 over file with given name, returns true if successful
bool AP_Filesystem::crc32(const char *fname, uint32_t& checksum) bool AP_Filesystem::crc32(const char *fname, uint32_t& checksum)
{ {
// Ensure value is initialized
checksum = 0;
// Open file in readonly mode // Open file in readonly mode
int fd = open(fname, O_RDONLY); int fd = open(fname, O_RDONLY);
if (fd == -1) { if (fd == -1) {