mirror of https://github.com/ArduPilot/ardupilot
AP_AHRS: send vision-speed-estimates to EKF3
This commit is contained in:
parent
c7817eaca1
commit
cad9889656
|
@ -1480,6 +1480,9 @@ void AP_AHRS_NavEKF::writeExtNavVelData(const Vector3f &vel, float err, uint32_t
|
|||
#if HAL_NAVEKF2_AVAILABLE
|
||||
EKF2.writeExtNavVelData(vel, err, timeStamp_ms, delay_ms);
|
||||
#endif
|
||||
#if HAL_NAVEKF3_AVAILABLE
|
||||
EKF3.writeExtNavVelData(vel, err, timeStamp_ms, delay_ms);
|
||||
#endif
|
||||
}
|
||||
|
||||
// inhibit GPS usage
|
||||
|
|
Loading…
Reference in New Issue