From 774332ea02d93f76d0831449bd829072428f7422 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Thu, 12 Mar 2015 20:10:41 +0900 Subject: [PATCH] Replay: fixup after inertial nav and baro glitch removal --- Tools/Replay/Replay.pde | 8 +------- 1 file changed, 1 insertion(+), 7 deletions(-) diff --git a/Tools/Replay/Replay.pde b/Tools/Replay/Replay.pde index 3a1728d974..9c5416ad79 100644 --- a/Tools/Replay/Replay.pde +++ b/Tools/Replay/Replay.pde @@ -35,12 +35,10 @@ #include #include #include -#include #include #include #include #include -#include #include #include #include @@ -73,9 +71,7 @@ static AP_Baro barometer; static AP_GPS gps; static AP_Compass_HIL compass; static AP_AHRS_NavEKF ahrs(ins, barometer, gps); -static GPS_Glitch gps_glitch(gps); -static Baro_Glitch baro_glitch(barometer); -static AP_InertialNav inertial_nav(ahrs, barometer, gps_glitch, baro_glitch); +static AP_InertialNav_NavEKF inertial_nav(ahrs); static AP_Vehicle::FixedWing aparm; static AP_Airspeed airspeed(aparm); static DataFlash_File dataflash("logs"); @@ -219,7 +215,6 @@ void setup() barometer.setHIL(0); barometer.update(); compass.init(); - inertial_nav.init(); ins.set_hil_mode(); switch (update_rate) { @@ -270,7 +265,6 @@ void setup() hal.scheduler->millis()*0.001f); ahrs.set_home(loc); compass.set_initial_location(loc.lat, loc.lng); - inertial_nav.setup_home_position(); done_home_init = true; } }