Browse Source

ArduCopter: bug fix - initialise inertial nav

master
rmackay9 12 years ago
parent
commit
269e02ee93
  1. 4
      ArduCopter/system.pde

4
ArduCopter/system.pde

@ -252,6 +252,10 @@ static void init_ardupilot() @@ -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

Loading…
Cancel
Save