|
|
|
@ -76,7 +76,7 @@ void SoloGimbalEKF::RunEKF(float delta_time, const Vector3f &delta_angles, const
@@ -76,7 +76,7 @@ void SoloGimbalEKF::RunEKF(float delta_time, const Vector3f &delta_angles, const
|
|
|
|
|
bool main_ekf_healthy = false; |
|
|
|
|
nav_filter_status main_ekf_status; |
|
|
|
|
|
|
|
|
|
const AP_AHRS_NavEKF &_ahrs = AP::ahrs_navekf(); |
|
|
|
|
const auto &_ahrs = AP::ahrs(); |
|
|
|
|
|
|
|
|
|
if (_ahrs.get_filter_status(main_ekf_status)) { |
|
|
|
|
if (main_ekf_status.flags.attitude) { |
|
|
|
@ -597,7 +597,7 @@ void SoloGimbalEKF::predictCovariance()
@@ -597,7 +597,7 @@ void SoloGimbalEKF::predictCovariance()
|
|
|
|
|
// Fuse the SoloGimbalEKF velocity estimates - this enables alevel reference to be maintained during constant turns
|
|
|
|
|
void SoloGimbalEKF::fuseVelocity() |
|
|
|
|
{ |
|
|
|
|
const AP_AHRS_NavEKF &_ahrs = AP::ahrs_navekf(); |
|
|
|
|
const auto &_ahrs = AP::ahrs(); |
|
|
|
|
|
|
|
|
|
if (!_ahrs.have_inertial_nav()) { |
|
|
|
|
return; |
|
|
|
@ -668,7 +668,7 @@ void SoloGimbalEKF::fuseVelocity()
@@ -668,7 +668,7 @@ void SoloGimbalEKF::fuseVelocity()
|
|
|
|
|
// check for new magnetometer data and update store measurements if available
|
|
|
|
|
void SoloGimbalEKF::readMagData() |
|
|
|
|
{ |
|
|
|
|
const AP_AHRS_NavEKF &_ahrs = AP::ahrs_navekf(); |
|
|
|
|
const auto &_ahrs = AP::ahrs(); |
|
|
|
|
|
|
|
|
|
if (_ahrs.get_compass() && |
|
|
|
|
_ahrs.get_compass()->use_for_yaw() && |
|
|
|
@ -867,7 +867,7 @@ float SoloGimbalEKF::calcMagHeadingInnov()
@@ -867,7 +867,7 @@ float SoloGimbalEKF::calcMagHeadingInnov()
|
|
|
|
|
Tms[1][2] = sinPhi; |
|
|
|
|
Tms[2][2] = cosTheta*cosPhi; |
|
|
|
|
|
|
|
|
|
const AP_AHRS_NavEKF &_ahrs = AP::ahrs_navekf(); |
|
|
|
|
const auto &_ahrs = AP::ahrs(); |
|
|
|
|
|
|
|
|
|
// get earth magnetic field estimate from main ekf if available to take advantage of main ekf magnetic field learning
|
|
|
|
|
Vector3f earth_magfield = Vector3f(0,0,0); |
|
|
|
|