From 270bac4472c6531fd1fac1bd649294ba22438300 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 18 Oct 2014 12:14:34 +1100 Subject: [PATCH] AP_AHRS: make get_position() const This allows use from within AP_Mission --- libraries/AP_AHRS/AP_AHRS.h | 2 +- libraries/AP_AHRS/AP_AHRS_DCM.cpp | 2 +- libraries/AP_AHRS/AP_AHRS_DCM.h | 2 +- libraries/AP_AHRS/AP_AHRS_NavEKF.cpp | 2 +- libraries/AP_AHRS/AP_AHRS_NavEKF.h | 2 +- 5 files changed, 5 insertions(+), 5 deletions(-) diff --git a/libraries/AP_AHRS/AP_AHRS.h b/libraries/AP_AHRS/AP_AHRS.h index 3e6841452f..597e6fe33f 100644 --- a/libraries/AP_AHRS/AP_AHRS.h +++ b/libraries/AP_AHRS/AP_AHRS.h @@ -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; diff --git a/libraries/AP_AHRS/AP_AHRS_DCM.cpp b/libraries/AP_AHRS/AP_AHRS_DCM.cpp index fd015cdd07..6d5510e096 100644 --- a/libraries/AP_AHRS/AP_AHRS_DCM.cpp +++ b/libraries/AP_AHRS/AP_AHRS_DCM.cpp @@ -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; diff --git a/libraries/AP_AHRS/AP_AHRS_DCM.h b/libraries/AP_AHRS/AP_AHRS_DCM.h index 76160c09e5..015e32b405 100644 --- a/libraries/AP_AHRS/AP_AHRS_DCM.h +++ b/libraries/AP_AHRS/AP_AHRS_DCM.h @@ -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); diff --git a/libraries/AP_AHRS/AP_AHRS_NavEKF.cpp b/libraries/AP_AHRS/AP_AHRS_NavEKF.cpp index 224e7a9ba7..f17e4a80db 100644 --- a/libraries/AP_AHRS/AP_AHRS_NavEKF.cpp +++ b/libraries/AP_AHRS/AP_AHRS_NavEKF.cpp @@ -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; diff --git a/libraries/AP_AHRS/AP_AHRS_NavEKF.h b/libraries/AP_AHRS/AP_AHRS_NavEKF.h index d03ffdc173..bb8a42feb1 100644 --- a/libraries/AP_AHRS/AP_AHRS_NavEKF.h +++ b/libraries/AP_AHRS/AP_AHRS_NavEKF.h @@ -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);