AP_AHRS: if DCM has no yaw source then don't fallback when hovering

this copes with quadplanes with no compass. With a compass we are
better off using EKF when not in fly-forward as it will give better
height control.

This makes QHOVER for takeoff in quadplanes with no compass a lot more
flyable
This commit is contained in:
Andrew Tridgell 2022-12-18 08:06:45 +11:00
parent 56c8cffc07
commit 87b4b031bf
3 changed files with 14 additions and 0 deletions

View File

@ -1904,6 +1904,11 @@ AP_AHRS::EKFType AP_AHRS::active_EKF_type(void) const
if (ret != EKFType::NONE &&
(_vehicle_class == VehicleClass::FIXED_WING ||
_vehicle_class == VehicleClass::GROUND)) {
if (!dcm.yaw_source_available() && !fly_forward) {
// if we don't have a DCM yaw source available and we are
// in a non-fly-forward mode then we are best off using the EKF
return ret;
}
bool should_use_gps = true;
nav_filter_status filt_state;
#if HAL_NAVEKF2_AVAILABLE

View File

@ -1254,3 +1254,9 @@ bool AP_AHRS_DCM::get_relative_position_D_origin(float &posD) const
void AP_AHRS_DCM::send_ekf_status_report(GCS_MAVLINK &link) const
{
}
// return true if DCM has a yaw source available
bool AP_AHRS_DCM::yaw_source_available(void) const
{
return AP::compass().use_for_yaw();
}

View File

@ -124,6 +124,9 @@ public:
void send_ekf_status_report(class GCS_MAVLINK &link) const override;
// return true if DCM has a yaw source
bool yaw_source_available(void) const;
private:
// settable parameters