mirror of https://github.com/ArduPilot/ardupilot
AP_IOMCU: use crc32_small() in AP_IOMCU
the slower speed is not noticible and this saves 1k ram
This commit is contained in:
parent
31f7a62cdc
commit
34f5b40919
|
@ -763,12 +763,12 @@ bool AP_IOMCU::check_crc(void)
|
|||
hal.console->printf("failed to find %s\n", fw_name);
|
||||
return false;
|
||||
}
|
||||
uint32_t crc = crc_crc32(0, fw, fw_size);
|
||||
uint32_t crc = crc32_small(0, fw, fw_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);
|
||||
crc = crc32_small(crc, &b, 1);
|
||||
}
|
||||
|
||||
uint32_t io_crc = 0;
|
||||
|
|
|
@ -397,11 +397,11 @@ bool AP_IOMCU::verify_rev3(uint32_t fw_size_local)
|
|||
return ret;
|
||||
}
|
||||
|
||||
sum = crc_crc32(0, fw, fw_size_local);
|
||||
sum = crc32_small(0, fw, fw_size_local);
|
||||
|
||||
/* 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);
|
||||
sum = crc32_small(sum, &fill_blank, 1);
|
||||
}
|
||||
|
||||
/* request CRC from IO */
|
||||
|
|
|
@ -642,7 +642,7 @@ void AP_IOMCU_FW::calculate_fw_crc(void)
|
|||
|
||||
for (unsigned p = 0; p < APP_SIZE_MAX; p += 4) {
|
||||
uint32_t bytes = *(uint32_t *)(p + APP_LOAD_ADDRESS);
|
||||
sum = crc_crc32(sum, (const uint8_t *)&bytes, sizeof(bytes));
|
||||
sum = crc32_small(sum, (const uint8_t *)&bytes, sizeof(bytes));
|
||||
}
|
||||
|
||||
reg_setup.crc[0] = sum & 0xFFFF;
|
||||
|
|
Loading…
Reference in New Issue