diff --git a/libraries/AP_NavEKF/EKFGSF_yaw.cpp b/libraries/AP_NavEKF/EKFGSF_yaw.cpp index 7427f2218c..7d33a00fd7 100644 --- a/libraries/AP_NavEKF/EKFGSF_yaw.cpp +++ b/libraries/AP_NavEKF/EKFGSF_yaw.cpp @@ -592,11 +592,11 @@ float EKFGSF_yaw::gaussianDensity(const uint8_t mdl_idx) const return normDist; } -bool EKFGSF_yaw::getLogData(float *yaw_composite, float *yaw_composite_variance, float yaw[N_MODELS_EKFGSF], float innov_VN[N_MODELS_EKFGSF], float innov_VE[N_MODELS_EKFGSF], float weight[N_MODELS_EKFGSF]) +bool EKFGSF_yaw::getLogData(float &yaw_composite, float &yaw_composite_variance, float yaw[N_MODELS_EKFGSF], float innov_VN[N_MODELS_EKFGSF], float innov_VE[N_MODELS_EKFGSF], float weight[N_MODELS_EKFGSF]) { if (vel_fuse_running) { - *yaw_composite = GSF.yaw; - *yaw_composite_variance = GSF.yaw_variance; + yaw_composite = GSF.yaw; + yaw_composite_variance = GSF.yaw_variance; for (uint8_t mdl_idx = 0; mdl_idx < N_MODELS_EKFGSF; mdl_idx++) { yaw[mdl_idx] = EKF[mdl_idx].X[2]; innov_VN[mdl_idx] = EKF[mdl_idx].innov[0]; @@ -647,12 +647,12 @@ Matrix3f EKFGSF_yaw::updateRotMat(const Matrix3f &R, const Vector3f &g) return ret; } -bool EKFGSF_yaw::getYawData(float *yaw, float *yawVariance) +bool EKFGSF_yaw::getYawData(float &yaw, float &yawVariance) { if (!vel_fuse_running) { return false; } - *yaw = GSF.yaw; - *yawVariance = GSF.yaw_variance; + yaw = GSF.yaw; + yawVariance = GSF.yaw_variance; return true; } \ No newline at end of file diff --git a/libraries/AP_NavEKF/EKFGSF_yaw.h b/libraries/AP_NavEKF/EKFGSF_yaw.h index 64a1864aff..84ed6bc9c0 100644 --- a/libraries/AP_NavEKF/EKFGSF_yaw.h +++ b/libraries/AP_NavEKF/EKFGSF_yaw.h @@ -27,11 +27,11 @@ public: // get solution data for logging // return false if yaw estimation is inactive - bool getLogData(float *yaw_composite, float *yaw_composite_variance, float yaw[N_MODELS_EKFGSF], float innov_VN[N_MODELS_EKFGSF], float innov_VE[N_MODELS_EKFGSF], float weight[N_MODELS_EKFGSF]); + bool getLogData(float &yaw_composite, float &yaw_composite_variance, float yaw[N_MODELS_EKFGSF], float innov_VN[N_MODELS_EKFGSF], float innov_VE[N_MODELS_EKFGSF], float weight[N_MODELS_EKFGSF]); // get yaw estimated and corresponding variance // return false if yaw estimation is inactive - bool getYawData(float *yaw, float *yawVariance); + bool getYawData(float &yaw, float &yawVariance); private: