AP_AHRS_NavEKF: accept external position estimates into AHRS

This commit is contained in:
Peter Barker 2018-03-08 11:44:53 +11:00 committed by Randy Mackay
parent 20412dc0db
commit aae4ed2553
2 changed files with 10 additions and 0 deletions

View File

@ -1164,6 +1164,13 @@ void AP_AHRS_NavEKF::writeBodyFrameOdom(float quality, const Vector3f &delPos,
EKF3.writeBodyFrameOdom(quality, delPos, delAng, delTime, timeStamp_ms, posOffset);
}
// Write position and quaternion data from an external navigation system
void AP_AHRS_NavEKF::writeExtNavData(const Vector3f &sensOffset, const Vector3f &pos, const Quaternion &quat, float posErr, float angErr, uint32_t timeStamp_ms, uint32_t resetTime_ms)
{
EKF2.writeExtNavData(sensOffset, pos, quat, posErr, angErr, timeStamp_ms, resetTime_ms);
}
// inhibit GPS usage
uint8_t AP_AHRS_NavEKF::setInhibitGPS(void)
{

View File

@ -163,6 +163,9 @@ public:
// write body odometry measurements to the EKF
void writeBodyFrameOdom(float quality, const Vector3f &delPos, const Vector3f &delAng, float delTime, uint32_t timeStamp_ms, const Vector3f &posOffset);
// Write position and quaternion data from an external navigation system
void writeExtNavData(const Vector3f &sensOffset, const Vector3f &pos, const Quaternion &quat, float posErr, float angErr, uint32_t timeStamp_ms, uint32_t resetTime_ms) override;
// inhibit GPS usage
uint8_t setInhibitGPS(void);