Browse Source

Replay: Remove AP_InertialNav

mission-4.1.18
khancyr 8 years ago committed by Peter Barker
parent
commit
9ade6cd579
  1. 3
      Tools/Replay/Replay.cpp
  2. 2
      Tools/Replay/Replay.h
  3. 1
      Tools/Replay/make.inc
  4. 1
      Tools/Replay/wscript

3
Tools/Replay/Replay.cpp

@ -689,9 +689,6 @@ void Replay::read_sensors(const char *type) @@ -689,9 +689,6 @@ void Replay::read_sensors(const char *type)
if (run_ahrs) {
_vehicle.ahrs.update();
if (_vehicle.ahrs.get_home().lat != 0) {
_vehicle.inertial_nav.update(_vehicle.ins.get_delta_time());
}
if ((downsample == 0 || ++output_counter % downsample == 0) && !logmatch) {
write_ekf_logs();
}

2
Tools/Replay/Replay.h

@ -35,7 +35,6 @@ @@ -35,7 +35,6 @@
#include <AP_Compass/AP_Compass.h>
#include <AP_Baro/AP_Baro.h>
#include <AP_InertialSensor/AP_InertialSensor.h>
#include <AP_InertialNav/AP_InertialNav.h>
#include <AP_NavEKF2/AP_NavEKF2.h>
#include <AP_NavEKF3/AP_NavEKF3.h>
#include <AP_Mission/AP_Mission.h>
@ -67,7 +66,6 @@ public: @@ -67,7 +66,6 @@ public:
NavEKF2 EKF2{&ahrs, rng};
NavEKF3 EKF3{&ahrs, rng};
AP_AHRS_NavEKF ahrs{EKF2, EKF3};
AP_InertialNav_NavEKF inertial_nav{ahrs};
AP_Vehicle::FixedWing aparm;
AP_Airspeed airspeed;
AP_Int32 unused; // logging is magic for Replay; this is unused

1
Tools/Replay/make.inc

@ -17,7 +17,6 @@ LIBRARIES += AP_AHRS @@ -17,7 +17,6 @@ LIBRARIES += AP_AHRS
LIBRARIES += AP_Compass
LIBRARIES += AP_Baro
LIBRARIES += AP_InertialSensor
LIBRARIES += AP_InertialNav
LIBRARIES += AP_NavEKF2
LIBRARIES += AP_NavEKF3
LIBRARIES += AP_Mission

1
Tools/Replay/wscript

@ -13,7 +13,6 @@ def build(bld): @@ -13,7 +13,6 @@ def build(bld):
name=vehicle + '_libs',
ap_vehicle=vehicle,
ap_libraries=bld.ap_common_vehicle_libraries() + [
'AP_InertialNav',
'AP_Beacon',
],
)

Loading…
Cancel
Save