AP_AHRS: add interface for use of visual odometry data
This commit is contained in:
parent
fb7104f4e3
commit
3b82f60b08
@ -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)
|
||||
{
|
||||
|
@ -153,6 +153,9 @@ public:
|
||||
// write optical flow measurements to EKF
|
||||
void writeOptFlowMeas(uint8_t &rawFlowQuality, Vector2f &rawFlowRates, Vector2f &rawGyroRates, uint32_t &msecFlowMeas, const Vector3f &posOffset);
|
||||
|
||||
// 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);
|
||||
|
||||
// inhibit GPS usage
|
||||
uint8_t setInhibitGPS(void);
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user