AP_AHRS: make get_position() const

This allows use from within AP_Mission
This commit is contained in:
Andrew Tridgell 2014-10-18 12:14:34 +11:00
parent be17bfd972
commit 270bac4472
5 changed files with 5 additions and 5 deletions

View File

@ -202,7 +202,7 @@ public:
// get our current position estimate. Return true if a position is available,
// otherwise false. This call fills in lat, lng and alt
virtual bool get_position(struct Location &loc) = 0;
virtual bool get_position(struct Location &loc) const = 0;
// return a wind estimation vector, in m/s
virtual Vector3f wind_estimate(void) = 0;

View File

@ -872,7 +872,7 @@ float AP_AHRS_DCM::get_error_yaw(void)
// return our current position estimate using
// dead-reckoning or GPS
bool AP_AHRS_DCM::get_position(struct Location &loc)
bool AP_AHRS_DCM::get_position(struct Location &loc) const
{
loc.lat = _last_lat;
loc.lng = _last_lng;

View File

@ -83,7 +83,7 @@ public:
void reset_attitude(const float &roll, const float &pitch, const float &yaw);
// dead-reckoning support
virtual bool get_position(struct Location &loc);
virtual bool get_position(struct Location &loc) const;
// status reporting
float get_error_rp(void);

View File

@ -129,7 +129,7 @@ void AP_AHRS_NavEKF::reset_attitude(const float &_roll, const float &_pitch, con
}
// dead-reckoning support
bool AP_AHRS_NavEKF::get_position(struct Location &loc)
bool AP_AHRS_NavEKF::get_position(struct Location &loc) const
{
if (using_EKF() && EKF.getLLH(loc)) {
return true;

View File

@ -56,7 +56,7 @@ public:
void reset_attitude(const float &roll, const float &pitch, const float &yaw);
// dead-reckoning support
bool get_position(struct Location &loc);
bool get_position(struct Location &loc) const;
// status reporting of estimated error
float get_error_rp(void);