mirror of https://github.com/ArduPilot/ardupilot
AP_InertialNav: remove ability to use DCM as AHRS
This commit is contained in:
parent
0d391533b0
commit
a3ee979b9c
|
@ -84,6 +84,4 @@ public:
|
|||
virtual float get_velocity_z() const = 0;
|
||||
};
|
||||
|
||||
#if AP_AHRS_NAVEKF_AVAILABLE
|
||||
#include "AP_InertialNav_NavEKF.h"
|
||||
#endif
|
||||
|
|
|
@ -2,8 +2,6 @@
|
|||
#include <AP_Baro/AP_Baro.h>
|
||||
#include "AP_InertialNav.h"
|
||||
|
||||
#if AP_AHRS_NAVEKF_AVAILABLE
|
||||
|
||||
/*
|
||||
A wrapper around the AP_InertialNav class which uses the NavEKF
|
||||
filter if available, and falls back to the AP_InertialNav filter
|
||||
|
@ -106,5 +104,3 @@ float AP_InertialNav_NavEKF::get_velocity_z() const
|
|||
{
|
||||
return _velocity_cm.z;
|
||||
}
|
||||
|
||||
#endif // AP_AHRS_NAVEKF_AVAILABLE
|
||||
|
|
Loading…
Reference in New Issue