mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-24 09:38:29 -04:00
AP_NavEKF: constify getLastYawResetAngle
This commit is contained in:
parent
7c20577ee0
commit
758c5a7d7f
@ -5584,7 +5584,7 @@ void NavEKF::alignMagStateDeclination()
|
|||||||
|
|
||||||
// return the amount of yaw angle change due to the last yaw angle reset in radians
|
// 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
|
// returns the time of the last yaw angle reset or 0 if no reset has ever occurred
|
||||||
uint32_t NavEKF::getLastYawResetAngle(float &yawAng)
|
uint32_t NavEKF::getLastYawResetAngle(float &yawAng) const
|
||||||
{
|
{
|
||||||
yawAng = yawResetAngle;
|
yawAng = yawResetAngle;
|
||||||
return lastYawReset_ms;
|
return lastYawReset_ms;
|
||||||
|
@ -278,7 +278,7 @@ public:
|
|||||||
|
|
||||||
// return the amount of yaw angle change due to the last yaw angle reset in radians
|
// 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
|
// 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
|
// 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
|
// returns the time of the last reset or 0 if no reset has ever occurred
|
||||||
|
Loading…
Reference in New Issue
Block a user