mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 08:38:36 -04:00
AP_AHRS: add accessor for GSF yaw estimator
This commit is contained in:
parent
001f6a29ee
commit
bdf903b862
@ -3132,6 +3132,31 @@ enum Rotation AP_AHRS::get_view_rotation(void) const
|
||||
return _view?_view->get_rotation():ROTATION_NONE;
|
||||
}
|
||||
|
||||
// check if non-compass sensor is providing yaw. Allows compass pre-arm checks to be bypassed
|
||||
const EKFGSF_yaw *AP_AHRS::get_yaw_estimator(void) const
|
||||
{
|
||||
switch (active_EKF_type()) {
|
||||
#if HAL_NAVEKF2_AVAILABLE
|
||||
case EKFType::TWO:
|
||||
return EKF2.get_yawEstimator();
|
||||
#endif
|
||||
case EKFType::NONE:
|
||||
#if HAL_NAVEKF3_AVAILABLE
|
||||
case EKFType::THREE:
|
||||
return EKF3.get_yawEstimator();
|
||||
#endif
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
case EKFType::SIM:
|
||||
#endif
|
||||
#if HAL_EXTERNAL_AHRS_ENABLED
|
||||
case EKFType::EXTERNAL:
|
||||
#endif
|
||||
return nullptr;
|
||||
}
|
||||
// since there is no default case above, this is unreachable
|
||||
return nullptr;
|
||||
}
|
||||
|
||||
// singleton instance
|
||||
AP_AHRS *AP_AHRS::_singleton;
|
||||
|
||||
|
@ -53,6 +53,9 @@ class AP_AHRS_View;
|
||||
|
||||
#include <AP_NMEA_Output/AP_NMEA_Output.h>
|
||||
|
||||
// fwd declare GSF estimator
|
||||
class EKFGSF_yaw;
|
||||
|
||||
class AP_AHRS {
|
||||
friend class AP_AHRS_View;
|
||||
public:
|
||||
@ -594,6 +597,9 @@ public:
|
||||
// get the view's rotation, or ROTATION_NONE
|
||||
enum Rotation get_view_rotation(void) const;
|
||||
|
||||
// get access to an EKFGSF_yaw estimator
|
||||
const EKFGSF_yaw *get_yaw_estimator(void) const;
|
||||
|
||||
private:
|
||||
|
||||
// optional view class
|
||||
|
Loading…
Reference in New Issue
Block a user