diff --git a/ArduCopter/ekf_check.cpp b/ArduCopter/ekf_check.cpp index ce4d333e42..d0f6982fb5 100644 --- a/ArduCopter/ekf_check.cpp +++ b/ArduCopter/ekf_check.cpp @@ -225,7 +225,6 @@ void Copter::check_ekf_reset() AP::logger().Write_Event(LogEvent::EKF_YAW_RESET); } -#if AP_AHRS_NAVEKF_AVAILABLE && (HAL_NAVEKF2_AVAILABLE || HAL_NAVEKF3_AVAILABLE) // check for change in primary EKF, reset attitude target and log. AC_PosControl handles position target adjustment if ((ahrs.get_primary_core_index() != ekf_primary_core) && (ahrs.get_primary_core_index() != -1)) { attitude_control->inertial_frame_reset(); @@ -233,7 +232,6 @@ void Copter::check_ekf_reset() AP::logger().Write_Error(LogErrorSubsystem::EKF_PRIMARY, LogErrorCode(ekf_primary_core)); gcs().send_text(MAV_SEVERITY_WARNING, "EKF primary changed:%d", (unsigned)ekf_primary_core); } -#endif } // check for high vibrations affecting altitude control