Browse Source

AP_NavEKF3: pass by const reference when needed

master
Pierre Kancir 6 years ago committed by Randy Mackay
parent
commit
340429fbbb
  1. 4
      libraries/AP_NavEKF3/AP_NavEKF3_core.cpp
  2. 4
      libraries/AP_NavEKF3/AP_NavEKF3_core.h

4
libraries/AP_NavEKF3/AP_NavEKF3_core.cpp

@ -1393,7 +1393,7 @@ void NavEKF3_core::StoreQuatReset() @@ -1393,7 +1393,7 @@ void NavEKF3_core::StoreQuatReset()
}
// Rotate the stored output quaternion history through a quaternion rotation
void NavEKF3_core::StoreQuatRotate(Quaternion deltaQuat)
void NavEKF3_core::StoreQuatRotate(const Quaternion &deltaQuat)
{
outputDataNew.quat = outputDataNew.quat*deltaQuat;
// write current measurement to entire table
@ -1665,7 +1665,7 @@ Vector3f NavEKF3_core::calcRotVecVariances() @@ -1665,7 +1665,7 @@ Vector3f NavEKF3_core::calcRotVecVariances()
}
// initialise the quaternion covariances using rotation vector variances
void NavEKF3_core::initialiseQuatCovariances(Vector3f &rotVarVec)
void NavEKF3_core::initialiseQuatCovariances(const Vector3f &rotVarVec)
{
// calculate an equivalent rotation vector from the quaternion
float q0 = stateStruct.quat[0];

4
libraries/AP_NavEKF3/AP_NavEKF3_core.h

@ -561,7 +561,7 @@ private: @@ -561,7 +561,7 @@ private:
void StoreQuatReset(void);
// Rotate the stored output quaternion history through a quaternion rotation
void StoreQuatRotate(Quaternion deltaQuat);
void StoreQuatRotate(const Quaternion &deltaQuat);
// store altimeter data
void StoreBaro();
@ -790,7 +790,7 @@ private: @@ -790,7 +790,7 @@ private:
Vector3f calcRotVecVariances(void);
// initialise the quaternion covariances using rotation vector variances
void initialiseQuatCovariances(Vector3f &rotVarVec);
void initialiseQuatCovariances(const Vector3f &rotVarVec);
// update timing statistics structure
void updateTimingStatistics(void);

Loading…
Cancel
Save