From 49d20364cb0ef8e6f32733300bab895a4c93f1d3 Mon Sep 17 00:00:00 2001 From: Pierre Kancir Date: Wed, 19 Dec 2018 17:43:35 +0100 Subject: [PATCH] AP_NavEKF2: pass quaternion by const reference --- libraries/AP_NavEKF2/AP_NavEKF2_core.cpp | 2 +- libraries/AP_NavEKF2/AP_NavEKF2_core.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_NavEKF2/AP_NavEKF2_core.cpp b/libraries/AP_NavEKF2/AP_NavEKF2_core.cpp index 5f2c3bc093..484951f03c 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2_core.cpp +++ b/libraries/AP_NavEKF2/AP_NavEKF2_core.cpp @@ -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 diff --git a/libraries/AP_NavEKF2/AP_NavEKF2_core.h b/libraries/AP_NavEKF2/AP_NavEKF2_core.h index 0eedac250c..1e04e35902 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2_core.h +++ b/libraries/AP_NavEKF2/AP_NavEKF2_core.h @@ -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();