Browse Source

AP_NavEKF2: pass quaternion by const reference

mission-4.1.18
Pierre Kancir 6 years ago committed by Randy Mackay
parent
commit
49d20364cb
  1. 2
      libraries/AP_NavEKF2/AP_NavEKF2_core.cpp
  2. 2
      libraries/AP_NavEKF2/AP_NavEKF2_core.h

2
libraries/AP_NavEKF2/AP_NavEKF2_core.cpp

@ -1379,7 +1379,7 @@ void NavEKF2_core::StoreQuatReset() @@ -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

2
libraries/AP_NavEKF2/AP_NavEKF2_core.h

@ -527,7 +527,7 @@ private: @@ -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…
Cancel
Save