AP_AHRS: Enable EKF3 default airspeed to be set
AP_AHRS: Send default airspeed to EKF2
This commit is contained in:
parent
de0040ad69
commit
9cf75bf22e
@ -1455,6 +1455,16 @@ void AP_AHRS_NavEKF::writeExtNavData(const Vector3f &pos, const Quaternion &quat
|
||||
#endif
|
||||
}
|
||||
|
||||
// Writes the default equivalent airspeed in m/s to be used in forward flight if a measured airspeed is required and not available.
|
||||
void AP_AHRS_NavEKF::writeDefaultAirSpeed(float airspeed)
|
||||
{
|
||||
#if HAL_NAVEKF2_AVAILABLE
|
||||
EKF2.writeDefaultAirSpeed(airspeed);
|
||||
#endif
|
||||
#if HAL_NAVEKF3_AVAILABLE
|
||||
EKF3.writeDefaultAirSpeed(airspeed);
|
||||
#endif
|
||||
}
|
||||
|
||||
// inhibit GPS usage
|
||||
uint8_t AP_AHRS_NavEKF::setInhibitGPS(void)
|
||||
|
@ -179,6 +179,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);
|
||||
|
||||
// Writes the default equivalent airspeed in m/s to be used in forward flight if a measured airspeed is required and not available.
|
||||
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;
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user