From e3dd0d33e733b024a95f1f77bfc809f42087db5e Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 12 Dec 2019 18:30:16 +1100 Subject: [PATCH] Copter: allow NavEKFs to be compiled out --- ArduCopter/Parameters.cpp | 6 +++++- ArduCopter/ekf_check.cpp | 3 ++- 2 files changed, 7 insertions(+), 2 deletions(-) diff --git a/ArduCopter/Parameters.cpp b/ArduCopter/Parameters.cpp index a7cd211ea3..b36cfc4c4a 100644 --- a/ArduCopter/Parameters.cpp +++ b/ArduCopter/Parameters.cpp @@ -627,13 +627,17 @@ const AP_Param::Info Copter::var_info[] = { // @Path: ../libraries/AP_RCMapper/AP_RCMapper.cpp GOBJECT(rcmap, "RCMAP_", RCMapper), +#if HAL_NAVEKF2_AVAILABLE // @Group: EK2_ // @Path: ../libraries/AP_NavEKF2/AP_NavEKF2.cpp GOBJECTN(ahrs.EKF2, NavEKF2, "EK2_", NavEKF2), - +#endif + +#if HAL_NAVEKF3_AVAILABLE // @Group: EK3_ // @Path: ../libraries/AP_NavEKF3/AP_NavEKF3.cpp GOBJECTN(ahrs.EKF3, NavEKF3, "EK3_", NavEKF3), +#endif #if MODE_AUTO_ENABLED == ENABLED // @Group: MIS_ diff --git a/ArduCopter/ekf_check.cpp b/ArduCopter/ekf_check.cpp index 16fa644670..05edeccfcf 100644 --- a/ArduCopter/ekf_check.cpp +++ b/ArduCopter/ekf_check.cpp @@ -198,7 +198,8 @@ void Copter::check_ekf_reset() AP::logger().Write_Event(LogEvent::EKF_YAW_RESET); } -#if AP_AHRS_NAVEKF_AVAILABLE +#if AP_AHRS_NAVEKF_AVAILABLE && HAL_NAVEKF2_AVAILABLE + // check for change in primary EKF (log only, AC_WPNav handles position target adjustment) if ((ahrs.EKF2.getPrimaryCoreIndex() != ekf_primary_core) && (ahrs.EKF2.getPrimaryCoreIndex() != -1)) { attitude_control->inertial_frame_reset();