|
|
|
@ -383,10 +383,9 @@ bool AP_IOMCU::verify_rev3(uint32_t fw_size_local)
@@ -383,10 +383,9 @@ bool AP_IOMCU::verify_rev3(uint32_t fw_size_local)
|
|
|
|
|
{ |
|
|
|
|
bool ret; |
|
|
|
|
uint32_t sum = 0; |
|
|
|
|
uint32_t bytes_read = 0; |
|
|
|
|
uint32_t crc = 0; |
|
|
|
|
uint32_t fw_size_remote; |
|
|
|
|
uint8_t fill_blank = 0xff; |
|
|
|
|
const uint8_t fill_blank = 0xff; |
|
|
|
|
|
|
|
|
|
debug("verify..."); |
|
|
|
|
|
|
|
|
@ -398,23 +397,11 @@ bool AP_IOMCU::verify_rev3(uint32_t fw_size_local)
@@ -398,23 +397,11 @@ bool AP_IOMCU::verify_rev3(uint32_t fw_size_local)
|
|
|
|
|
return ret; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
/* read through the firmware file again and calculate the checksum */ |
|
|
|
|
while (bytes_read < fw_size_local) { |
|
|
|
|
uint32_t n = fw_size_local - bytes_read; |
|
|
|
|
if (n > 4) { |
|
|
|
|
n = 4; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
/* calculate crc32 sum */ |
|
|
|
|
sum = crc_crc32(sum, &fw[bytes_read], n); |
|
|
|
|
|
|
|
|
|
bytes_read += n; |
|
|
|
|
} |
|
|
|
|
sum = crc_crc32(0, fw, fw_size_local); |
|
|
|
|
|
|
|
|
|
/* fill the rest with 0xff */ |
|
|
|
|
while (bytes_read < fw_size_remote) { |
|
|
|
|
/* fill the rest of CRC with 0xff */ |
|
|
|
|
for (uint32_t i=0; i<fw_size_remote - fw_size_local; i++) { |
|
|
|
|
sum = crc_crc32(sum, &fill_blank, 1); |
|
|
|
|
bytes_read++; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
/* request CRC from IO */ |
|
|
|
|