AP_AHRS: remove writeExtNavData sensOffset argument

EKF pulls this directly from AP_VisualOdom
This commit is contained in:
Randy Mackay 2020-04-13 12:26:13 +09:00 committed by Andrew Tridgell
parent 8749f30c64
commit 79afc70cdb
3 changed files with 4 additions and 4 deletions

View File

@ -551,7 +551,7 @@ public:
virtual bool get_hgt_ctrl_limit(float &limit) const WARN_IF_UNUSED { return false; };
// Write position and quaternion data from an external navigation system
virtual void writeExtNavData(const Vector3f &sensOffset, const Vector3f &pos, const Quaternion &quat, float posErr, float angErr, uint32_t timeStamp_ms, uint32_t resetTime_ms) { }
virtual void writeExtNavData(const Vector3f &pos, const Quaternion &quat, float posErr, float angErr, uint32_t timeStamp_ms, uint32_t resetTime_ms) { }
// return current vibration vector for primary IMU
Vector3f get_vibration(void) const;

View File

@ -1448,10 +1448,10 @@ void AP_AHRS_NavEKF::writeBodyFrameOdom(float quality, const Vector3f &delPos,
}
// 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)
void AP_AHRS_NavEKF::writeExtNavData(const Vector3f &pos, const Quaternion &quat, float posErr, float angErr, uint32_t timeStamp_ms, uint32_t resetTime_ms)
{
#if HAL_NAVEKF2_AVAILABLE
EKF2.writeExtNavData(sensOffset, pos, quat, posErr, angErr, timeStamp_ms, resetTime_ms);
EKF2.writeExtNavData(pos, quat, posErr, angErr, timeStamp_ms, resetTime_ms);
#endif
}

View File

@ -180,7 +180,7 @@ public:
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;
void writeExtNavData(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);