diff --git a/libraries/AP_VisualOdom/AP_VisualOdom_IntelT265.cpp b/libraries/AP_VisualOdom/AP_VisualOdom_IntelT265.cpp index 9db3204aa6aa0..6ddb0d901c0fd 100644 --- a/libraries/AP_VisualOdom/AP_VisualOdom_IntelT265.cpp +++ b/libraries/AP_VisualOdom/AP_VisualOdom_IntelT265.cpp @@ -130,7 +130,7 @@ void AP_VisualOdom_IntelT265::rotate_attitude(Quaternion &attitude) const bool AP_VisualOdom_IntelT265::align_sensor_to_vehicle(const Vector3f &position, const Quaternion &attitude) { // do not align to ahrs if it is using us as its yaw source - if (AP::ahrs().is_ext_nav_used_for_yaw()) { + if (AP::ahrs().using_noncompass_for_yaw()) { return false; }