mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_NavEKF2: constify getLastYawResetAngle
This commit is contained in:
parent
758c5a7d7f
commit
52ed075405
@ -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);
|
||||
}
|
||||
|
@ -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
|
||||
|
@ -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;
|
||||
|
@ -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…
Reference in New Issue
Block a user