mirror of https://github.com/ArduPilot/ardupilot
AP_BoardConfig: increase uavcan bus settle time to 2s
needed to ensure zubax mag has time to come up
This commit is contained in:
parent
7c6bdfb95c
commit
d9b3b7a9b5
|
@ -229,7 +229,7 @@ void AP_BoardConfig::px4_setup_canbus(void)
|
|||
hal.console->printf("UAVCAN: failed to start\n");
|
||||
}
|
||||
// give time for canbus drivers to register themselves
|
||||
hal.scheduler->delay(1000);
|
||||
hal.scheduler->delay(2000);
|
||||
}
|
||||
if (px4.can_enable >= 2) {
|
||||
if (px4_start_driver(uavcan_main, "uavcan", "start fw")) {
|
||||
|
|
Loading…
Reference in New Issue