InertialNav: remove GPS glitch protection and baro reference

This commit is contained in:
Randy Mackay 2015-03-13 11:02:01 +09:00
parent 6f6847c025
commit 4461952534
3 changed files with 4 additions and 11 deletions

View File

@ -7,7 +7,6 @@
#include <AP_InertialSensor.h> // ArduPilot Mega IMU Library #include <AP_InertialSensor.h> // ArduPilot Mega IMU Library
#include <AP_Baro.h> // ArduPilot Mega Barometer Library #include <AP_Baro.h> // ArduPilot Mega Barometer Library
#include <AP_Buffer.h> // FIFO buffer library #include <AP_Buffer.h> // FIFO buffer library
#include <AP_GPS_Glitch.h> // GPS Glitch detection library
#include "../AP_NavEKF/AP_Nav_Common.h" // definitions shared by inertial and ekf nav filters #include "../AP_NavEKF/AP_Nav_Common.h" // definitions shared by inertial and ekf nav filters
/* /*
@ -29,9 +28,7 @@ class AP_InertialNav
public: public:
// Constructor // Constructor
AP_InertialNav(AP_AHRS &ahrs) : AP_InertialNav() {}
_ahrs(ahrs)
{}
/** /**
* update - updates velocity and position estimates using latest info from accelerometers * update - updates velocity and position estimates using latest info from accelerometers
@ -112,10 +109,6 @@ public:
* @return climbrate in cm/s (positive up) * @return climbrate in cm/s (positive up)
*/ */
virtual float get_velocity_z() const = 0; virtual float get_velocity_z() const = 0;
protected:
AP_AHRS &_ahrs; // reference to ahrs object
}; };
#if AP_AHRS_NAVEKF_AVAILABLE #if AP_AHRS_NAVEKF_AVAILABLE

View File

@ -19,7 +19,7 @@ void AP_InertialNav_NavEKF::update(float dt)
_ahrs_ekf.get_NavEKF().getPosNED(_relpos_cm); _ahrs_ekf.get_NavEKF().getPosNED(_relpos_cm);
_relpos_cm *= 100; // convert to cm _relpos_cm *= 100; // convert to cm
_haveabspos = _ahrs.get_position(_abspos); _haveabspos = _ahrs_ekf.get_position(_abspos);
_ahrs_ekf.get_NavEKF().getVelNED(_velocity_cm); _ahrs_ekf.get_NavEKF().getVelNED(_velocity_cm);
_velocity_cm *= 100; // convert to cm/s _velocity_cm *= 100; // convert to cm/s

View File

@ -16,8 +16,8 @@ class AP_InertialNav_NavEKF : public AP_InertialNav
{ {
public: public:
// Constructor // Constructor
AP_InertialNav_NavEKF(AP_AHRS_NavEKF &ahrs, AP_Baro &baro, GPS_Glitch& gps_glitch) : AP_InertialNav_NavEKF(AP_AHRS_NavEKF &ahrs) :
AP_InertialNav(ahrs), AP_InertialNav(),
_haveabspos(false), _haveabspos(false),
_ahrs_ekf(ahrs) _ahrs_ekf(ahrs)
{} {}