mirror of https://github.com/ArduPilot/ardupilot
AP_IOMCU: fixed repeated upload of IO fw
This commit is contained in:
parent
1e2065e381
commit
ba0fb3d9d2
|
@ -651,11 +651,10 @@ bool AP_IOMCU::check_crc(void)
|
|||
}
|
||||
uint32_t crc = crc_crc32(0, fw, fw_size);
|
||||
|
||||
// pad to max size
|
||||
while (fw_size < flash_size) {
|
||||
// pad CRC to max size
|
||||
for (uint32_t i=0; i<flash_size-fw_size; i++) {
|
||||
uint8_t b = 0xff;
|
||||
crc = crc_crc32(crc, &b, 1);
|
||||
fw_size++;
|
||||
}
|
||||
|
||||
uint32_t io_crc = 0;
|
||||
|
|
|
@ -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)
|
|||
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;
|
||||
}
|
||||
sum = crc_crc32(0, fw, fw_size_local);
|
||||
|
||||
/* calculate crc32 sum */
|
||||
sum = crc_crc32(sum, &fw[bytes_read], n);
|
||||
|
||||
bytes_read += n;
|
||||
}
|
||||
|
||||
/* 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 */
|
||||
|
|
Loading…
Reference in New Issue