AP_InertialNav: Remove unneeded methods

This commit is contained in:
Michael du Breuil 2019-06-28 13:56:04 +00:00 committed by Randy Mackay
parent bbcb976e73
commit 13840337ec
3 changed files with 3 additions and 99 deletions

View File

@ -27,23 +27,14 @@ public:
/** /**
* update - updates velocity and position estimates using latest info from accelerometers * update - updates velocity and position estimates using latest info from accelerometers
* augmented with gps and baro readings * augmented with gps and baro readings
*
* @param dt : time since last update in seconds
*/ */
virtual void update(float dt) = 0; virtual void update(void) = 0;
/** /**
* get_filter_status : returns filter status as a series of flags * get_filter_status : returns filter status as a series of flags
*/ */
virtual nav_filter_status get_filter_status() const = 0; virtual nav_filter_status get_filter_status() const = 0;
/**
* get_origin - returns the inertial navigation origin in lat/lon/alt
*
* @return origin Location
*/
virtual struct Location get_origin() const = 0;
// //
// XY Axis specific methods // XY Axis specific methods
// //
@ -55,24 +46,6 @@ public:
*/ */
virtual const Vector3f& get_position() const = 0; virtual const Vector3f& get_position() const = 0;
/**
* get_llh - updates the provided location with the latest calculated location including absolute altitude
* returns true on success (i.e. the EKF knows it's latest position), false on failure
*/
virtual bool get_location(struct Location &loc) const = 0;
/**
* get_latitude - returns the latitude of the current position estimation in 100 nano degrees (i.e. degree value multiplied by 10,000,000)
* @return
*/
virtual int32_t get_latitude() const = 0;
/**
* get_longitude - returns the longitude of the current position estimation in 100 nano degrees (i.e. degree value multiplied by 10,000,000)
* @return
*/
virtual int32_t get_longitude() const = 0;
/** /**
* get_velocity - returns the current velocity in cm/s * get_velocity - returns the current velocity in cm/s
* *

View File

@ -12,7 +12,7 @@
/** /**
update internal state update internal state
*/ */
void AP_InertialNav_NavEKF::update(float dt) void AP_InertialNav_NavEKF::update()
{ {
// get the NE position relative to the local earth frame origin // get the NE position relative to the local earth frame origin
Vector2f posNE; Vector2f posNE;
@ -27,9 +27,6 @@ void AP_InertialNav_NavEKF::update(float dt)
_relpos_cm.z = - posD * 100; // convert from m in NED to cm in NEU _relpos_cm.z = - posD * 100; // convert from m in NED to cm in NEU
} }
// get the absolute WGS-84 position
_haveabspos = _ahrs_ekf.get_position(_abspos);
// get the velocity relative to the local earth frame // get the velocity relative to the local earth frame
Vector3f velNED; Vector3f velNED;
if (_ahrs_ekf.get_velocity_NED(velNED)) { if (_ahrs_ekf.get_velocity_NED(velNED)) {
@ -48,19 +45,6 @@ nav_filter_status AP_InertialNav_NavEKF::get_filter_status() const
return status; return status;
} }
/**
* get_origin - returns the inertial navigation origin in lat/lon/alt
*/
struct Location AP_InertialNav_NavEKF::get_origin() const
{
struct Location ret;
if (!_ahrs_ekf.get_origin(ret)) {
// initialise location to all zeros if EKF origin not yet set
ret.zero();
}
return ret;
}
/** /**
* get_position - returns the current position relative to the home location in cm. * get_position - returns the current position relative to the home location in cm.
* *
@ -71,32 +55,6 @@ const Vector3f &AP_InertialNav_NavEKF::get_position(void) const
return _relpos_cm; return _relpos_cm;
} }
/**
* get_location - updates the provided location with the latest calculated location
* returns true on success (i.e. the EKF knows it's latest position), false on failure
*/
bool AP_InertialNav_NavEKF::get_location(struct Location &loc) const
{
return _ahrs_ekf.get_location(loc);
}
/**
* get_latitude - returns the latitude of the current position estimation in 100 nano degrees (i.e. degree value multiplied by 10,000,000)
*/
int32_t AP_InertialNav_NavEKF::get_latitude() const
{
return _abspos.lat;
}
/**
* get_longitude - returns the longitude of the current position estimation in 100 nano degrees (i.e. degree value multiplied by 10,000,000)
* @return
*/
int32_t AP_InertialNav_NavEKF::get_longitude() const
{
return _abspos.lng;
}
/** /**
* get_velocity - returns the current velocity in cm/s * get_velocity - returns the current velocity in cm/s
* *

View File

@ -13,27 +13,19 @@ public:
// Constructor // Constructor
AP_InertialNav_NavEKF(AP_AHRS_NavEKF &ahrs) : AP_InertialNav_NavEKF(AP_AHRS_NavEKF &ahrs) :
AP_InertialNav(), AP_InertialNav(),
_haveabspos(false),
_ahrs_ekf(ahrs) _ahrs_ekf(ahrs)
{} {}
/** /**
update internal state update internal state
*/ */
void update(float dt) override; void update() override;
/** /**
* get_filter_status - returns filter status as a series of flags * get_filter_status - returns filter status as a series of flags
*/ */
nav_filter_status get_filter_status() const override; nav_filter_status get_filter_status() const override;
/**
* get_origin - returns the inertial navigation origin in lat/lon/alt
*
* @return origin Location
*/
struct Location get_origin() const override;
/** /**
* get_position - returns the current position relative to the home location in cm. * get_position - returns the current position relative to the home location in cm.
* *
@ -43,23 +35,6 @@ public:
*/ */
const Vector3f& get_position() const override; const Vector3f& get_position() const override;
/**
* get_llh - updates the provided location with the latest calculated location including absolute altitude
* returns true on success (i.e. the EKF knows it's latest position), false on failure
*/
bool get_location(struct Location &loc) const override;
/**
* get_latitude - returns the latitude of the current position estimation in 100 nano degrees (i.e. degree value multiplied by 10,000,000)
*/
int32_t get_latitude() const override;
/**
* get_longitude - returns the longitude of the current position estimation in 100 nano degrees (i.e. degree value multiplied by 10,000,000)
* @return
*/
int32_t get_longitude() const override;
/** /**
* get_velocity - returns the current velocity in cm/s * get_velocity - returns the current velocity in cm/s
* *
@ -95,7 +70,5 @@ public:
private: private:
Vector3f _relpos_cm; // NEU Vector3f _relpos_cm; // NEU
Vector3f _velocity_cm; // NEU Vector3f _velocity_cm; // NEU
struct Location _abspos;
bool _haveabspos;
AP_AHRS_NavEKF &_ahrs_ekf; AP_AHRS_NavEKF &_ahrs_ekf;
}; };