AP_AHRS: writeExtNavData accepts delay
This commit is contained in:
parent
c28fd27b02
commit
762e82d49d
@ -557,7 +557,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 &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, uint16_t delay_ms, uint32_t resetTime_ms) { }
|
||||
|
||||
// return current vibration vector for primary IMU
|
||||
Vector3f get_vibration(void) const;
|
||||
|
@ -1453,13 +1453,13 @@ 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 &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, uint16_t delay_ms, uint32_t resetTime_ms)
|
||||
{
|
||||
#if HAL_NAVEKF2_AVAILABLE
|
||||
EKF2.writeExtNavData(pos, quat, posErr, angErr, timeStamp_ms, resetTime_ms);
|
||||
EKF2.writeExtNavData(pos, quat, posErr, angErr, timeStamp_ms, delay_ms, resetTime_ms);
|
||||
#endif
|
||||
#if HAL_NAVEKF3_AVAILABLE
|
||||
EKF3.writeExtNavData(pos, quat, posErr, angErr, timeStamp_ms, resetTime_ms);
|
||||
EKF3.writeExtNavData(pos, quat, posErr, angErr, timeStamp_ms, delay_ms, resetTime_ms);
|
||||
#endif
|
||||
}
|
||||
|
||||
|
@ -184,7 +184,7 @@ public:
|
||||
void writeDefaultAirSpeed(float airspeed);
|
||||
|
||||
// Write position and quaternion data from an external navigation system
|
||||
void writeExtNavData(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, uint16_t delay_ms, uint32_t resetTime_ms) override;
|
||||
|
||||
// inhibit GPS usage
|
||||
uint8_t setInhibitGPS(void);
|
||||
|
Loading…
Reference in New Issue
Block a user