InertialNav: add get_location method

This commit is contained in:
Randy Mackay 2015-02-25 23:13:17 +09:00
parent 9ecbd0e30f
commit 558018d839
3 changed files with 21 additions and 0 deletions

View File

@ -61,6 +61,12 @@ public:
*/
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

View File

@ -62,6 +62,15 @@ const Vector3f &AP_InertialNav_NavEKF::get_position(void) const
return _relpos_cm;
}
/**
* get_location - updates the provided location with the latest calculated locatoin
* 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_NavEKF().getLLH(loc);
}
/**
* get_latitude - returns the latitude of the current position estimation in 100 nano degrees (i.e. degree value multiplied by 10,000,000)
*/

View File

@ -48,6 +48,12 @@ public:
*/
const Vector3f& get_position() const;
/**
* 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;
/**
* get_latitude - returns the latitude of the current position estimation in 100 nano degrees (i.e. degree value multiplied by 10,000,000)
*/