From c6dd39773d4417367c451c0d16a7117cfad2ca71 Mon Sep 17 00:00:00 2001 From: Josh Henderson Date: Sat, 11 Sep 2021 04:08:25 -0400 Subject: [PATCH] ArduPlane: inav use _xy() --- ArduPlane/quadplane.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index 21a9c3c5cd..5df5c23667 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -2331,7 +2331,7 @@ void QuadPlane::vtol_position_controller(void) // reset position controller xy target to current position // because we only want velocity control (no position control) - const Vector3f& curr_pos = inertial_nav.get_position(); + const Vector2f& curr_pos = inertial_nav.get_position_xy(); pos_control->set_pos_target_xy_cm(curr_pos.x, curr_pos.y); pos_control->set_accel_desired_xy_cmss(Vector2f());