AP_BoardConfig: fold init_vehicle back into AP_Vehicle init method

This commit is contained in:
Peter Barker 2020-02-18 12:59:18 +11:00 committed by Andrew Tridgell
parent 0ca6b7cf77
commit a7c493d037
1 changed files with 0 additions and 6 deletions

View File

@ -322,12 +322,6 @@ void AP_BoardConfig::init()
printf("SDCard failed to start\n");
}
#endif
// run any the vehicle initialization routines
AP_Vehicle *vehicle = AP::vehicle();
if (vehicle) {
vehicle->init_vehicle();
}
}
// set default value for BRD_SAFETY_MASK