mirror of https://github.com/ArduPilot/ardupilot
AP_Filesystem: crc32: Ensure checksum value is initialized
This commit is contained in:
parent
46e4588cf7
commit
c48759f4ba
|
@ -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) {
|
||||||
|
|
Loading…
Reference in New Issue