Browse Source

AP_NavEKF2: constify getLastYawResetAngle

mission-4.1.18
Randy Mackay 9 years ago
parent
commit
52ed075405
  1. 4
      libraries/AP_NavEKF2/AP_NavEKF2.cpp
  2. 2
      libraries/AP_NavEKF2/AP_NavEKF2.h
  3. 2
      libraries/AP_NavEKF2/AP_NavEKF2_Outputs.cpp
  4. 2
      libraries/AP_NavEKF2/AP_NavEKF2_core.h

4
libraries/AP_NavEKF2/AP_NavEKF2.cpp

@ -809,10 +809,10 @@ bool NavEKF2::getHeightControlLimit(float &height) const @@ -809,10 +809,10 @@ bool NavEKF2::getHeightControlLimit(float &height) 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 NavEKF2::getLastYawResetAngle(float &yawAng)
uint32_t NavEKF2::getLastYawResetAngle(float &yawAng) const
{
if (!core) {
return false;
return 0;
}
return core->getLastYawResetAngle(yawAng);
}

2
libraries/AP_NavEKF2/AP_NavEKF2.h

@ -225,7 +225,7 @@ public: @@ -225,7 +225,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 due to the last position reset in metres
// returns the time of the last reset or 0 if no reset has ever occurred

2
libraries/AP_NavEKF2/AP_NavEKF2_Outputs.cpp

@ -122,7 +122,7 @@ void NavEKF2_core::getQuaternion(Quaternion& ret) const @@ -122,7 +122,7 @@ void NavEKF2_core::getQuaternion(Quaternion& ret) 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 NavEKF2_core::getLastYawResetAngle(float &yawAng)
uint32_t NavEKF2_core::getLastYawResetAngle(float &yawAng) const
{
yawAng = yawResetAngle;
return lastYawReset_ms;

2
libraries/AP_NavEKF2/AP_NavEKF2_core.h

@ -246,7 +246,7 @@ public: @@ -246,7 +246,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 due to the last position reset in metres
// returns the time of the last reset or 0 if no reset has ever occurred

Loading…
Cancel
Save