Browse Source

AP_NavEKF3: added a getter function to infer the source index used by ekf3

master
nrt 3 years ago committed by Randy Mackay
parent
commit
0c65cd1b47
  1. 6
      libraries/AP_NavEKF3/AP_NavEKF3.cpp
  2. 3
      libraries/AP_NavEKF3/AP_NavEKF3.h

6
libraries/AP_NavEKF3/AP_NavEKF3.cpp

@ -1239,6 +1239,12 @@ void NavEKF3::getAccelBias(int8_t instance, Vector3f &accelBias) const @@ -1239,6 +1239,12 @@ void NavEKF3::getAccelBias(int8_t instance, Vector3f &accelBias) const
}
}
// returns active source set used by EKF3
uint8_t NavEKF3::get_active_source_set() const
{
return sources.get_active_source_set();
}
// reset body axis gyro bias estimates
void NavEKF3::resetGyroBias(void)
{

3
libraries/AP_NavEKF3/AP_NavEKF3.h

@ -97,6 +97,9 @@ public: @@ -97,6 +97,9 @@ public:
// An out of range instance (eg -1) returns data for the primary instance
void getAccelBias(int8_t instance, Vector3f &accelBias) const;
//returns index of the active source set used
uint8_t get_active_source_set() const;
// reset body axis gyro bias estimates
void resetGyroBias(void);

Loading…
Cancel
Save