diff --git a/Tools/Replay/Parameters.h b/Tools/Replay/Parameters.h index acd2d8188d..15ca8cc1c6 100644 --- a/Tools/Replay/Parameters.h +++ b/Tools/Replay/Parameters.h @@ -16,6 +16,7 @@ public: k_param_ahrs, k_param_airspeed, k_param_NavEKF, + k_param_NavEKF2, k_param_compass }; AP_Int8 dummy; diff --git a/Tools/Replay/Replay.cpp b/Tools/Replay/Replay.cpp index cc949376a9..4ac13e6fb4 100644 --- a/Tools/Replay/Replay.cpp +++ b/Tools/Replay/Replay.cpp @@ -43,6 +43,7 @@ #include #include #include +#include #include #include #include @@ -85,7 +86,8 @@ public: AP_SerialManager serial_manager; RangeFinder rng {serial_manager}; NavEKF EKF{&ahrs, barometer, rng}; - AP_AHRS_NavEKF ahrs {ins, barometer, gps, rng, EKF}; + NavEKF2 EKF2{&ahrs, barometer, rng}; + AP_AHRS_NavEKF ahrs {ins, barometer, gps, rng, EKF, EKF2}; AP_InertialNav_NavEKF inertial_nav{ahrs}; AP_Vehicle::FixedWing aparm; AP_Airspeed airspeed{aparm}; @@ -131,6 +133,10 @@ const AP_Param::Info ReplayVehicle::var_info[] PROGMEM = { // @Path: ../libraries/AP_NavEKF/AP_NavEKF.cpp GOBJECTN(EKF, NavEKF, "EKF_", NavEKF), + // @Group: EK2_ + // @Path: ../libraries/AP_NavEKF2/AP_NavEKF2.cpp + GOBJECTN(EKF2, NavEKF2, "EK2_", NavEKF2), + // @Group: COMPASS_ // @Path: ../libraries/AP_Compass/AP_Compass.cpp GOBJECT(compass, "COMPASS_", Compass), diff --git a/Tools/Replay/make.inc b/Tools/Replay/make.inc index fc2dfc757a..a8757f33ac 100644 --- a/Tools/Replay/make.inc +++ b/Tools/Replay/make.inc @@ -26,6 +26,7 @@ LIBRARIES += AP_Baro LIBRARIES += AP_InertialSensor LIBRARIES += AP_InertialNav LIBRARIES += AP_NavEKF +LIBRARIES += AP_NavEKF2 LIBRARIES += AP_Mission LIBRARIES += AP_Rally LIBRARIES += AP_BattMonitor