ArduCopter: bug fix - initialise inertial nav

This commit is contained in:
rmackay9 2012-12-04 14:00:51 +09:00
parent 5551f092be
commit 9c0984c505

View File

@ -252,6 +252,10 @@ static void init_ardupilot()
init_optflow();
}
#if INERTIAL_NAV_XY == ENABLED || INERTIAL_NAV_Z == ENABLED
// initialise inertial nav
inertial_nav.init();
#endif
// agmatthews USERHOOKS
#ifdef USERHOOK_INIT