mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-13 10:03:57 -03:00
AP_BoardConfig: raise UAVCAN startup time
new version needs a longer time to start sensors
This commit is contained in:
parent
dbefd87dd0
commit
5d5c398344
@ -150,7 +150,7 @@ void AP_BoardConfig::init()
|
||||
} else {
|
||||
hal.console->printf("UAVCAN: started\n");
|
||||
// give some time for CAN bus initialisation
|
||||
hal.scheduler->delay(500);
|
||||
hal.scheduler->delay(1500);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
Loading…
Reference in New Issue
Block a user