Replay: fixup after inertial nav and baro glitch removal

This commit is contained in:
Randy Mackay 2015-03-12 20:10:41 +09:00
parent 9c6531ebeb
commit 774332ea02
1 changed files with 1 additions and 7 deletions

View File

@ -35,12 +35,10 @@
#include <DataFlash.h>
#include <GCS_MAVLink.h>
#include <AP_GPS.h>
#include <AP_GPS_Glitch.h>
#include <AP_AHRS.h>
#include <SITL.h>
#include <AP_Compass.h>
#include <AP_Baro.h>
#include <AP_Baro_Glitch.h>
#include <AP_InertialSensor.h>
#include <AP_InertialNav.h>
#include <AP_NavEKF.h>
@ -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;
}
}