AP_NavEKF2: pass quaternion by const reference

This commit is contained in:
Pierre Kancir 2018-12-19 17:43:35 +01:00 committed by Randy Mackay
parent 3d08d02a66
commit 49d20364cb
2 changed files with 2 additions and 2 deletions

View File

@ -1379,7 +1379,7 @@ void NavEKF2_core::StoreQuatReset()
}
// Rotate the stored output quaternion history through a quaternion rotation
void NavEKF2_core::StoreQuatRotate(Quaternion deltaQuat)
void NavEKF2_core::StoreQuatRotate(const Quaternion &deltaQuat)
{
outputDataNew.quat = outputDataNew.quat*deltaQuat;
// write current measurement to entire table

View File

@ -527,7 +527,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();