ArduCopter: bug fix - initialise inertial nav
This commit is contained in:
parent
8d682b9812
commit
269e02ee93
@ -252,6 +252,10 @@ static void init_ardupilot()
|
|||||||
init_optflow();
|
init_optflow();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#if INERTIAL_NAV_XY == ENABLED || INERTIAL_NAV_Z == ENABLED
|
||||||
|
// initialise inertial nav
|
||||||
|
inertial_nav.init();
|
||||||
|
#endif
|
||||||
|
|
||||||
// agmatthews USERHOOKS
|
// agmatthews USERHOOKS
|
||||||
#ifdef USERHOOK_INIT
|
#ifdef USERHOOK_INIT
|
||||||
|
Loading…
Reference in New Issue
Block a user