From dddb285209358148fed2ef81d4f6c3a5e5eaf06c Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 17 Dec 2020 15:42:23 +1100 Subject: [PATCH] AP_NavEKF2: remove internal-only getTiltError method --- libraries/AP_NavEKF2/AP_NavEKF2.cpp | 9 --------- libraries/AP_NavEKF2/AP_NavEKF2.h | 4 ---- libraries/AP_NavEKF2/AP_NavEKF2_Logging.cpp | 4 +--- libraries/AP_NavEKF2/AP_NavEKF2_Outputs.cpp | 6 ------ libraries/AP_NavEKF2/AP_NavEKF2_core.h | 3 --- 5 files changed, 1 insertion(+), 25 deletions(-) diff --git a/libraries/AP_NavEKF2/AP_NavEKF2.cpp b/libraries/AP_NavEKF2/AP_NavEKF2.cpp index 49ba7ab39b..9d62a3f802 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2.cpp +++ b/libraries/AP_NavEKF2/AP_NavEKF2.cpp @@ -988,15 +988,6 @@ void NavEKF2::getGyroScaleErrorPercentage(int8_t instance, Vector3f &gyroScale) } } -// return tilt error convergence metric for the specified instance -void NavEKF2::getTiltError(int8_t instance, float &ang) const -{ - if (instance < 0 || instance >= num_cores) instance = primary; - if (core) { - core[instance].getTiltError(ang); - } -} - // reset body axis gyro bias estimates void NavEKF2::resetGyroBias(void) { diff --git a/libraries/AP_NavEKF2/AP_NavEKF2.h b/libraries/AP_NavEKF2/AP_NavEKF2.h index e7859ecf5f..058134abe9 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2.h +++ b/libraries/AP_NavEKF2/AP_NavEKF2.h @@ -102,10 +102,6 @@ public: // An out of range instance (eg -1) returns data for the primary instance void getGyroScaleErrorPercentage(int8_t instance, Vector3f &gyroScale) const; - // return tilt error convergence metric for the specified instance - // An out of range instance (eg -1) returns data for the primary instance - void getTiltError(int8_t instance, float &ang) const; - // reset body axis gyro bias estimates void resetGyroBias(void); diff --git a/libraries/AP_NavEKF2/AP_NavEKF2_Logging.cpp b/libraries/AP_NavEKF2/AP_NavEKF2_Logging.cpp index 4096329d85..dfb7b0d5c3 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2_Logging.cpp +++ b/libraries/AP_NavEKF2/AP_NavEKF2_Logging.cpp @@ -128,8 +128,6 @@ void NavEKF2_core::Log_Write_NKF4(uint64_t time_us) const getFilterTimeouts(timeoutStatus); getFilterStatus(solutionStatus); getFilterGpsStatus(gpsStatus); - float tiltError; - getTiltError(tiltError); const struct log_NKF4 pkt4{ LOG_PACKET_HEADER_INIT(LOG_NKF4_MSG), time_us : time_us, @@ -139,7 +137,7 @@ void NavEKF2_core::Log_Write_NKF4(uint64_t time_us) const sqrtvarH : (int16_t)(100*hgtVar), sqrtvarM : (int16_t)(100*tempVar), sqrtvarVT : (int16_t)(100*tasVar), - tiltErr : (float)tiltError, + tiltErr : tiltErrFilt, // tilt error convergence metric offsetNorth : (int8_t)(offset.x), offsetEast : (int8_t)(offset.y), faults : _faultStatus, diff --git a/libraries/AP_NavEKF2/AP_NavEKF2_Outputs.cpp b/libraries/AP_NavEKF2/AP_NavEKF2_Outputs.cpp index aa3f695d99..f9bd5f5ab1 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2_Outputs.cpp +++ b/libraries/AP_NavEKF2/AP_NavEKF2_Outputs.cpp @@ -105,12 +105,6 @@ void NavEKF2_core::getGyroScaleErrorPercentage(Vector3f &gyroScale) const gyroScale.z = 100.0f/stateStruct.gyro_scale.z - 100.0f; } -// return tilt error convergence metric -void NavEKF2_core::getTiltError(float &ang) const -{ - ang = tiltErrFilt; -} - // return the transformation matrix from XYZ (body) to NED axes void NavEKF2_core::getRotationBodyToNED(Matrix3f &mat) const { diff --git a/libraries/AP_NavEKF2/AP_NavEKF2_core.h b/libraries/AP_NavEKF2/AP_NavEKF2_core.h index 3261e3035d..d4ae686498 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2_core.h +++ b/libraries/AP_NavEKF2/AP_NavEKF2_core.h @@ -117,9 +117,6 @@ public: // return body axis gyro scale factor error as a percentage void getGyroScaleErrorPercentage(Vector3f &gyroScale) const; - // return tilt error convergence metric - void getTiltError(float &ang) const; - // reset body axis gyro bias estimates void resetGyroBias(void);