|
|
|
@ -1072,6 +1072,12 @@ void AP_AHRS_NavEKF::writeOptFlowMeas(uint8_t &rawFlowQuality, Vector2f &rawFlo
@@ -1072,6 +1072,12 @@ void AP_AHRS_NavEKF::writeOptFlowMeas(uint8_t &rawFlowQuality, Vector2f &rawFlo
|
|
|
|
|
EKF3.writeOptFlowMeas(rawFlowQuality, rawFlowRates, rawGyroRates, msecFlowMeas, posOffset); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// write body frame odometry measurements to the EKF
|
|
|
|
|
void AP_AHRS_NavEKF::writeBodyFrameOdom(float quality, const Vector3f &delPos, const Vector3f &delAng, float delTime, uint32_t timeStamp_ms, const Vector3f &posOffset) |
|
|
|
|
{ |
|
|
|
|
EKF3.writeBodyFrameOdom(quality, delPos, delAng, delTime, timeStamp_ms, posOffset); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// inhibit GPS usage
|
|
|
|
|
uint8_t AP_AHRS_NavEKF::setInhibitGPS(void) |
|
|
|
|
{ |
|
|
|
|