mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
AP_NavEKF2: pass quaternion by const reference
This commit is contained in:
parent
3d08d02a66
commit
49d20364cb
@ -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
|
||||
|
@ -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();
|
||||
|
Loading…
Reference in New Issue
Block a user