Copter: use AP_InertialNav_NavEKF when available

This commit is contained in:
Andrew Tridgell 2014-01-03 22:58:08 +11:00
parent 658110dd8c
commit 99b3517a47

View File

@ -666,7 +666,11 @@ static float G_Dt = 0.02;
//////////////////////////////////////////////////////////////////////////////// ////////////////////////////////////////////////////////////////////////////////
// Inertial Navigation // Inertial Navigation
//////////////////////////////////////////////////////////////////////////////// ////////////////////////////////////////////////////////////////////////////////
#if AP_AHRS_NAVEKF_AVAILABLE
static AP_InertialNav_NavEKF inertial_nav(ahrs, barometer, g_gps, gps_glitch);
#else
static AP_InertialNav inertial_nav(ahrs, barometer, g_gps, gps_glitch); static AP_InertialNav inertial_nav(ahrs, barometer, g_gps, gps_glitch);
#endif
//////////////////////////////////////////////////////////////////////////////// ////////////////////////////////////////////////////////////////////////////////
// Attitude, Position and Waypoint navigation objects // Attitude, Position and Waypoint navigation objects