mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 17:38:32 -04:00
Copter: use AP_InertialNav_NavEKF when available
This commit is contained in:
parent
658110dd8c
commit
99b3517a47
@ -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
|
||||||
|
Loading…
Reference in New Issue
Block a user