From 2c50ea56e81ed745baa7555f535e10edcd09f30c Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 14 Feb 2022 17:13:14 +1100 Subject: [PATCH] AP_Bootloader: raise timeout on FileRead calls this is needed to make it possible to update firmware over 56k SiK radios using CAN_FRAME --- Tools/AP_Bootloader/can.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Tools/AP_Bootloader/can.cpp b/Tools/AP_Bootloader/can.cpp index b62178754a..9f1427dbb5 100644 --- a/Tools/AP_Bootloader/can.cpp +++ b/Tools/AP_Bootloader/can.cpp @@ -171,7 +171,7 @@ static void handle_get_node_info(CanardInstance* ins, static void send_fw_read(void) { uint32_t now = AP_HAL::millis(); - if (now - fw_update.last_ms < 250) { + if (now - fw_update.last_ms < 750) { // the server may still be responding return; }