AP_NavEKF2: remove internal-only getTiltError method
This commit is contained in:
parent
5ad0ac6727
commit
dddb285209
@ -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
|
// reset body axis gyro bias estimates
|
||||||
void NavEKF2::resetGyroBias(void)
|
void NavEKF2::resetGyroBias(void)
|
||||||
{
|
{
|
||||||
|
@ -102,10 +102,6 @@ public:
|
|||||||
// An out of range instance (eg -1) returns data for the primary instance
|
// An out of range instance (eg -1) returns data for the primary instance
|
||||||
void getGyroScaleErrorPercentage(int8_t instance, Vector3f &gyroScale) const;
|
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
|
// reset body axis gyro bias estimates
|
||||||
void resetGyroBias(void);
|
void resetGyroBias(void);
|
||||||
|
|
||||||
|
@ -128,8 +128,6 @@ void NavEKF2_core::Log_Write_NKF4(uint64_t time_us) const
|
|||||||
getFilterTimeouts(timeoutStatus);
|
getFilterTimeouts(timeoutStatus);
|
||||||
getFilterStatus(solutionStatus);
|
getFilterStatus(solutionStatus);
|
||||||
getFilterGpsStatus(gpsStatus);
|
getFilterGpsStatus(gpsStatus);
|
||||||
float tiltError;
|
|
||||||
getTiltError(tiltError);
|
|
||||||
const struct log_NKF4 pkt4{
|
const struct log_NKF4 pkt4{
|
||||||
LOG_PACKET_HEADER_INIT(LOG_NKF4_MSG),
|
LOG_PACKET_HEADER_INIT(LOG_NKF4_MSG),
|
||||||
time_us : time_us,
|
time_us : time_us,
|
||||||
@ -139,7 +137,7 @@ void NavEKF2_core::Log_Write_NKF4(uint64_t time_us) const
|
|||||||
sqrtvarH : (int16_t)(100*hgtVar),
|
sqrtvarH : (int16_t)(100*hgtVar),
|
||||||
sqrtvarM : (int16_t)(100*tempVar),
|
sqrtvarM : (int16_t)(100*tempVar),
|
||||||
sqrtvarVT : (int16_t)(100*tasVar),
|
sqrtvarVT : (int16_t)(100*tasVar),
|
||||||
tiltErr : (float)tiltError,
|
tiltErr : tiltErrFilt, // tilt error convergence metric
|
||||||
offsetNorth : (int8_t)(offset.x),
|
offsetNorth : (int8_t)(offset.x),
|
||||||
offsetEast : (int8_t)(offset.y),
|
offsetEast : (int8_t)(offset.y),
|
||||||
faults : _faultStatus,
|
faults : _faultStatus,
|
||||||
|
@ -105,12 +105,6 @@ void NavEKF2_core::getGyroScaleErrorPercentage(Vector3f &gyroScale) const
|
|||||||
gyroScale.z = 100.0f/stateStruct.gyro_scale.z - 100.0f;
|
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
|
// return the transformation matrix from XYZ (body) to NED axes
|
||||||
void NavEKF2_core::getRotationBodyToNED(Matrix3f &mat) const
|
void NavEKF2_core::getRotationBodyToNED(Matrix3f &mat) const
|
||||||
{
|
{
|
||||||
|
@ -117,9 +117,6 @@ public:
|
|||||||
// return body axis gyro scale factor error as a percentage
|
// return body axis gyro scale factor error as a percentage
|
||||||
void getGyroScaleErrorPercentage(Vector3f &gyroScale) const;
|
void getGyroScaleErrorPercentage(Vector3f &gyroScale) const;
|
||||||
|
|
||||||
// return tilt error convergence metric
|
|
||||||
void getTiltError(float &ang) const;
|
|
||||||
|
|
||||||
// reset body axis gyro bias estimates
|
// reset body axis gyro bias estimates
|
||||||
void resetGyroBias(void);
|
void resetGyroBias(void);
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user