mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-25 18:18:49 -04:00
AP_IOMCU: use compressed interface for IO fw upload
This commit is contained in:
parent
230e1f681b
commit
9384bc9b03
@ -650,9 +650,8 @@ bool AP_IOMCU::check_crc(void)
|
|||||||
{
|
{
|
||||||
// flash size minus 4k bootloader
|
// flash size minus 4k bootloader
|
||||||
const uint32_t flash_size = 0x10000 - 0x1000;
|
const uint32_t flash_size = 0x10000 - 0x1000;
|
||||||
uint32_t fw_size;
|
|
||||||
|
|
||||||
fw = AP_ROMFS::find_file(fw_name, fw_size);
|
fw = AP_ROMFS::find_decompress(fw_name, fw_size);
|
||||||
if (!fw) {
|
if (!fw) {
|
||||||
hal.console->printf("failed to find %s\n", fw_name);
|
hal.console->printf("failed to find %s\n", fw_name);
|
||||||
return false;
|
return false;
|
||||||
@ -671,16 +670,22 @@ bool AP_IOMCU::check_crc(void)
|
|||||||
io_crc == crc) {
|
io_crc == crc) {
|
||||||
hal.console->printf("IOMCU: CRC ok\n");
|
hal.console->printf("IOMCU: CRC ok\n");
|
||||||
crc_is_ok = true;
|
crc_is_ok = true;
|
||||||
|
free(fw);
|
||||||
|
fw = nullptr;
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
const uint16_t magic = REBOOT_BL_MAGIC;
|
const uint16_t magic = REBOOT_BL_MAGIC;
|
||||||
write_registers(PAGE_SETUP, PAGE_REG_SETUP_REBOOT_BL, 1, &magic);
|
write_registers(PAGE_SETUP, PAGE_REG_SETUP_REBOOT_BL, 1, &magic);
|
||||||
|
|
||||||
if (!upload_fw(fw_name)) {
|
if (!upload_fw()) {
|
||||||
|
free(fw);
|
||||||
|
fw = nullptr;
|
||||||
AP_BoardConfig::sensor_config_error("Failed to update IO firmware");
|
AP_BoardConfig::sensor_config_error("Failed to update IO firmware");
|
||||||
}
|
}
|
||||||
|
|
||||||
|
free(fw);
|
||||||
|
fw = nullptr;
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -211,9 +211,10 @@ private:
|
|||||||
|
|
||||||
// firmware upload
|
// firmware upload
|
||||||
const char *fw_name = "io_firmware.bin";
|
const char *fw_name = "io_firmware.bin";
|
||||||
const uint8_t *fw;
|
uint8_t *fw;
|
||||||
|
uint32_t fw_size;
|
||||||
|
|
||||||
bool upload_fw(const char *filename);
|
bool upload_fw(void);
|
||||||
bool recv_byte_with_timeout(uint8_t *c, uint32_t timeout_ms);
|
bool recv_byte_with_timeout(uint8_t *c, uint32_t timeout_ms);
|
||||||
bool recv_bytes(uint8_t *p, uint32_t count);
|
bool recv_bytes(uint8_t *p, uint32_t count);
|
||||||
void drain(void);
|
void drain(void);
|
||||||
|
@ -63,11 +63,8 @@ extern const AP_HAL::HAL &hal;
|
|||||||
/*
|
/*
|
||||||
upload a firmware to the IOMCU
|
upload a firmware to the IOMCU
|
||||||
*/
|
*/
|
||||||
bool AP_IOMCU::upload_fw(const char *filename)
|
bool AP_IOMCU::upload_fw(void)
|
||||||
{
|
{
|
||||||
uint32_t fw_size;
|
|
||||||
fw = AP_ROMFS::find_file(filename, fw_size);
|
|
||||||
|
|
||||||
// set baudrate for bootloader
|
// set baudrate for bootloader
|
||||||
uart.begin(115200, 256, 256);
|
uart.begin(115200, 256, 256);
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user