AP_AHRS: Add accessor function for EKF3 yaw alignment status

This commit is contained in:
Paul Riseborough 2021-01-12 16:30:41 +11:00 committed by Andrew Tridgell
parent 6a603019d5
commit af2bf6097b
2 changed files with 39 additions and 0 deletions

View File

@ -2549,6 +2549,44 @@ bool AP_AHRS_NavEKF::get_variances(float &velVar, float &posVar, float &hgtVar,
return false; return false;
} }
bool AP_AHRS_NavEKF::yaw_alignment_complete(void) const
{
switch (ekf_type()) {
case EKFType::NONE:
// We are not using an EKF so no data
return true;
#if HAL_NAVEKF2_AVAILABLE
case EKFType::TWO: {
// not provided
return true;
}
#endif
#if HAL_NAVEKF3_AVAILABLE
case EKFType::THREE: {
// use EKF to get variance
Vector2f offset;
return EKF3.yawAlignmentComplete();
}
#endif
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
case EKFType::SITL:
// not provided
return true;
#endif
#if HAL_EXTERNAL_AHRS_ENABLED
case EKFType::EXTERNAL:
// not provided
return false;
#endif
}
return false;
}
// get a source's velocity innovations. source should be from 0 to 7 (see AP_NavEKF_Source::SourceXY) // get a source's velocity innovations. source should be from 0 to 7 (see AP_NavEKF_Source::SourceXY)
// returns true on success and results are placed in innovations and variances arguments // returns true on success and results are placed in innovations and variances arguments
bool AP_AHRS_NavEKF::get_vel_innovations_and_variances_for_source(uint8_t source, Vector3f &innovations, Vector3f &variances) const bool AP_AHRS_NavEKF::get_vel_innovations_and_variances_for_source(uint8_t source, Vector3f &innovations, Vector3f &variances) const

View File

@ -282,6 +282,7 @@ public:
void setTakeoffExpected(bool val); void setTakeoffExpected(bool val);
void setTouchdownExpected(bool val); void setTouchdownExpected(bool val);
bool yaw_alignment_complete(void) const;
bool getGpsGlitchStatus() const; bool getGpsGlitchStatus() const;