@ -517,7 +517,7 @@ const AP_Param::Info Rover::var_info[] PROGMEM = {
#if AP_AHRS_NAVEKF_AVAILABLE
// @Group: EKF_
// @Path: ../libraries/AP_NavEKF/AP_NavEKF.cpp
GOBJECTN(ahrs.get_NavEKF(), NavEKF, "EKF_", NavEKF),
GOBJECTN(EKF, NavEKF, "EKF_", NavEKF),
#endif
// @Group: MIS_
@ -30,11 +30,6 @@ Rover::Rover(void) :
in_log_download(false),
modes(&g.mode1),
ahrs(ins, barometer, gps, sonar),
#else
ahrs(ins, barometer, gps),
L1_controller(ahrs),
nav_controller(&L1_controller),
steerController(ahrs),
@ -158,9 +158,10 @@ private:
// Inertial Navigation EKF
AP_AHRS_NavEKF ahrs;
NavEKF EKF{&ahrs, barometer, sonar};
AP_AHRS_NavEKF ahrs {ins, barometer, gps, sonar, EKF};
AP_AHRS_DCM ahrs;
AP_AHRS_DCM ahrs {ins, barometer, gps};
AP_L1_Control L1_controller;