From 7c20577ee0073f88e5762d44e4b0a44453dc1aab Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Thu, 29 Oct 2015 17:31:02 +0900 Subject: [PATCH] AP_AHRS: constify getLastYawResetAngle --- libraries/AP_AHRS/AP_AHRS.h | 4 ++-- libraries/AP_AHRS/AP_AHRS_NavEKF.cpp | 4 ++-- libraries/AP_AHRS/AP_AHRS_NavEKF.h | 2 +- 3 files changed, 5 insertions(+), 5 deletions(-) diff --git a/libraries/AP_AHRS/AP_AHRS.h b/libraries/AP_AHRS/AP_AHRS.h index 888ed234ae..72766d09e4 100644 --- a/libraries/AP_AHRS/AP_AHRS.h +++ b/libraries/AP_AHRS/AP_AHRS.h @@ -388,8 +388,8 @@ public: // return the amount of yaw angle change due to the last yaw angle reset in radians // returns the time of the last yaw angle reset or 0 if no reset has ever occurred - virtual uint32_t getLastYawResetAngle(float &yawAng) { - return false; + virtual uint32_t getLastYawResetAngle(float &yawAng) const { + return 0; }; // return the amount of NE position change in metres due to the last reset diff --git a/libraries/AP_AHRS/AP_AHRS_NavEKF.cpp b/libraries/AP_AHRS/AP_AHRS_NavEKF.cpp index b60db8536b..ea9626ef6b 100644 --- a/libraries/AP_AHRS/AP_AHRS_NavEKF.cpp +++ b/libraries/AP_AHRS/AP_AHRS_NavEKF.cpp @@ -729,7 +729,7 @@ const char *AP_AHRS_NavEKF::prearm_failure_reason(void) const // return the amount of yaw angle change due to the last yaw angle reset in radians // returns the time of the last yaw angle reset or 0 if no reset has ever occurred -uint32_t AP_AHRS_NavEKF::getLastYawResetAngle(float &yawAng) +uint32_t AP_AHRS_NavEKF::getLastYawResetAngle(float &yawAng) const { switch (ekf_type()) { case 1: @@ -737,7 +737,7 @@ uint32_t AP_AHRS_NavEKF::getLastYawResetAngle(float &yawAng) case 2: return EKF2.getLastYawResetAngle(yawAng); } - return false; + return 0; } // return the amount of NE position change in metres due to the last reset diff --git a/libraries/AP_AHRS/AP_AHRS_NavEKF.h b/libraries/AP_AHRS/AP_AHRS_NavEKF.h index 47f77bc0f8..25005be525 100644 --- a/libraries/AP_AHRS/AP_AHRS_NavEKF.h +++ b/libraries/AP_AHRS/AP_AHRS_NavEKF.h @@ -165,7 +165,7 @@ public: // return the amount of yaw angle change due to the last yaw angle reset in radians // returns the time of the last yaw angle reset or 0 if no reset has ever occurred - uint32_t getLastYawResetAngle(float &yawAng); + uint32_t getLastYawResetAngle(float &yawAng) const; // return the amount of NE position change in metres due to the last reset // returns the time of the last reset or 0 if no reset has ever occurred