mirror of https://github.com/ArduPilot/ardupilot
AP_NavEKF3: remove internal-only getTiltError method
This commit is contained in:
parent
dddb285209
commit
b3bacdd33c
|
@ -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)
|
||||
{
|
||||
|
|
|
@ -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);
|
||||
|
||||
|
|
|
@ -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,
|
||||
|
|
|
@ -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
|
||||
{
|
||||
|
|
|
@ -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);
|
||||
|
||||
|
|
Loading…
Reference in New Issue