From b3bacdd33c96e503905171540b0bd454f01e62fb Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 17 Dec 2020 15:42:24 +1100 Subject: [PATCH] AP_NavEKF3: remove internal-only getTiltError method --- libraries/AP_NavEKF3/AP_NavEKF3.cpp | 9 --------- libraries/AP_NavEKF3/AP_NavEKF3.h | 4 ---- libraries/AP_NavEKF3/AP_NavEKF3_Logging.cpp | 4 +--- libraries/AP_NavEKF3/AP_NavEKF3_Outputs.cpp | 6 ------ libraries/AP_NavEKF3/AP_NavEKF3_core.h | 3 --- 5 files changed, 1 insertion(+), 25 deletions(-) diff --git a/libraries/AP_NavEKF3/AP_NavEKF3.cpp b/libraries/AP_NavEKF3/AP_NavEKF3.cpp index 39b8ab77d8..c52c845e23 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3.cpp +++ b/libraries/AP_NavEKF3/AP_NavEKF3.cpp @@ -1188,15 +1188,6 @@ void NavEKF3::getAccelBias(int8_t instance, Vector3f &accelBias) const } } -// return estimated 1-sigma tilt error for the specified instance in radians -void NavEKF3::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 NavEKF3::resetGyroBias(void) { diff --git a/libraries/AP_NavEKF3/AP_NavEKF3.h b/libraries/AP_NavEKF3/AP_NavEKF3.h index bec3be967a..c6c7dfa5aa 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3.h +++ b/libraries/AP_NavEKF3/AP_NavEKF3.h @@ -101,10 +101,6 @@ public: // An out of range instance (eg -1) returns data for the primary instance void getAccelBias(int8_t instance, Vector3f &accelBias) const; - // return estimated 1-sigma tilt error for the specified instance in radians - // 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_NavEKF3/AP_NavEKF3_Logging.cpp b/libraries/AP_NavEKF3/AP_NavEKF3_Logging.cpp index 70a9a33863..072b9a1d1b 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3_Logging.cpp +++ b/libraries/AP_NavEKF3/AP_NavEKF3_Logging.cpp @@ -147,8 +147,6 @@ void NavEKF3_core::Log_Write_XKF4(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_XKF4_MSG), time_us : time_us, @@ -158,7 +156,7 @@ void NavEKF3_core::Log_Write_XKF4(uint64_t time_us) const sqrtvarH : (int16_t)(100*hgtVar), sqrtvarM : (int16_t)(100*tempVar), sqrtvarVT : (int16_t)(100*tasVar), - tiltErr : tiltError, + tiltErr : sqrtf(MAX(tiltErrorVariance,0.0f)), // estimated 1-sigma tilt error in radians offsetNorth : (int8_t)(offset.x), offsetEast : (int8_t)(offset.y), faults : _faultStatus, diff --git a/libraries/AP_NavEKF3/AP_NavEKF3_Outputs.cpp b/libraries/AP_NavEKF3/AP_NavEKF3_Outputs.cpp index 6e18779d42..3cb010d6c0 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3_Outputs.cpp +++ b/libraries/AP_NavEKF3/AP_NavEKF3_Outputs.cpp @@ -123,12 +123,6 @@ void NavEKF3_core::getAccelBias(Vector3f &accelBias) const accelBias = stateStruct.accel_bias / dtEkfAvg; } -// return estimated 1-sigma tilt error in radians -void NavEKF3_core::getTiltError(float &ang) const -{ - ang = sqrtf(MAX(tiltErrorVariance,0.0f)); -} - // return the transformation matrix from XYZ (body) to NED axes void NavEKF3_core::getRotationBodyToNED(Matrix3f &mat) const { diff --git a/libraries/AP_NavEKF3/AP_NavEKF3_core.h b/libraries/AP_NavEKF3/AP_NavEKF3_core.h index baab4aee9b..21deb51b10 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3_core.h +++ b/libraries/AP_NavEKF3/AP_NavEKF3_core.h @@ -131,9 +131,6 @@ public: // return accelerometer bias in m/s/s void getAccelBias(Vector3f &accelBias) const; - // return estimated 1-sigma tilt error in radians - void getTiltError(float &ang) const; - // reset body axis gyro bias estimates void resetGyroBias(void);