@ -524,6 +524,12 @@ bool AP_NavEKF_Source::wheel_encoder_enabled(void) const
return false;
}
// returns active source set
uint8_t AP_NavEKF_Source::get_active_source_set() const
{
return active_source_set;
// return true if GPS yaw is enabled on any source
bool AP_NavEKF_Source::gps_yaw_enabled(void) const
@ -103,6 +103,9 @@ public:
// return true if wheel encoder is enabled on any source
bool wheel_encoder_enabled(void) const;
uint8_t get_active_source_set() const;
static const struct AP_Param::GroupInfo var_info[];
private: