mirror of https://github.com/ArduPilot/ardupilot
AP_NavEKF3: pass by const reference when needed
This commit is contained in:
parent
49d20364cb
commit
340429fbbb
|
@ -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()
|
|||
}
|
||||
|
||||
// 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];
|
||||
|
|
|
@ -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:
|
|||
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…
Reference in New Issue