mirror of https://github.com/ArduPilot/ardupilot
AP_NavEKF2: add accessor for GSF yaw estimator
This commit is contained in:
parent
bdf903b862
commit
0d8cf00c5a
|
@ -1595,3 +1595,12 @@ void NavEKF2::writeExtNavVelData(const Vector3f &vel, float err, uint32_t timeSt
|
|||
}
|
||||
}
|
||||
}
|
||||
|
||||
// get a yaw estimator instance
|
||||
const EKFGSF_yaw *NavEKF2::get_yawEstimator(void) const
|
||||
{
|
||||
if (core) {
|
||||
return core[primary].get_yawEstimator();
|
||||
}
|
||||
return nullptr;
|
||||
}
|
||||
|
|
|
@ -29,6 +29,7 @@
|
|||
#include <AP_NavEKF/AP_Nav_Common.h>
|
||||
|
||||
class NavEKF2_core;
|
||||
class EKFGSF_yaw;
|
||||
|
||||
class NavEKF2 {
|
||||
friend class NavEKF2_core;
|
||||
|
@ -305,6 +306,9 @@ public:
|
|||
// Writes the default equivalent airspeed in m/s to be used in forward flight if a measured airspeed is required and not available.
|
||||
void writeDefaultAirSpeed(float airspeed);
|
||||
|
||||
// get a yaw estimator instance
|
||||
const EKFGSF_yaw *get_yawEstimator(void) const;
|
||||
|
||||
private:
|
||||
uint8_t num_cores; // number of allocated cores
|
||||
uint8_t primary; // current primary core
|
||||
|
|
|
@ -327,6 +327,9 @@ public:
|
|||
|
||||
void Log_Write(uint64_t time_us);
|
||||
|
||||
// get a yaw estimator instance
|
||||
const EKFGSF_yaw *get_yawEstimator(void) const { return yawEstimator; }
|
||||
|
||||
private:
|
||||
EKFGSF_yaw *yawEstimator;
|
||||
AP_DAL &dal;
|
||||
|
|
Loading…
Reference in New Issue