mirror of https://github.com/ArduPilot/ardupilot
AP_Bootloader: raise timeout on FileRead calls
this is needed to make it possible to update firmware over 56k SiK radios using CAN_FRAME
This commit is contained in:
parent
19661fe981
commit
2c50ea56e8
|
@ -171,7 +171,7 @@ static void handle_get_node_info(CanardInstance* ins,
|
||||||
static void send_fw_read(void)
|
static void send_fw_read(void)
|
||||||
{
|
{
|
||||||
uint32_t now = AP_HAL::millis();
|
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
|
// the server may still be responding
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
Loading…
Reference in New Issue