diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index 1bf6aae74a..26acbe7a7a 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -2250,7 +2250,7 @@ void QuadPlane::vtol_position_controller(void) pos_control->set_desired_accel_xy(0.0f,0.0f); // run horizontal velocity controller - pos_control->update_vel_controller_xy(); + pos_control->update_xy_controller(); // nav roll and pitch are controller by position controller plane.nav_roll_cd = pos_control->get_roll();