mirror of https://github.com/ArduPilot/ardupilot
AP_NavEKF3: constify EKFGSF_getYaw
This commit is contained in:
parent
754002525e
commit
a2cca60beb
|
@ -1509,7 +1509,7 @@ bool NavEKF3_core::EKFGSF_resetMainFilterYaw()
|
|||
}
|
||||
|
||||
// returns true on success and populates yaw (in radians) and yawVariance (rad^2)
|
||||
bool NavEKF3_core::EKFGSF_getYaw(float& yaw, float& yawVariance)
|
||||
bool NavEKF3_core::EKFGSF_getYaw(float &yaw, float &yawVariance) const
|
||||
{
|
||||
// return immediately if no yaw estimator
|
||||
if (yawEstimator == nullptr) {
|
||||
|
|
|
@ -957,7 +957,7 @@ private:
|
|||
bool EKFGSF_resetMainFilterYaw();
|
||||
|
||||
// returns true on success and populates yaw (in radians) and yawVariance (rad^2)
|
||||
bool EKFGSF_getYaw(float &yaw, float &yawVariance);
|
||||
bool EKFGSF_getYaw(float &yaw, float &yawVariance) const;
|
||||
|
||||
// Fusion of body frame X and Y axis drag specific forces for multi-rotor wind estimation
|
||||
void FuseDragForces();
|
||||
|
|
Loading…
Reference in New Issue