From ff2ae1d7d18c5d35d1f02e02bc5c4d7ee5e8fd49 Mon Sep 17 00:00:00 2001 From: Leonard Hall Date: Wed, 12 May 2021 13:32:42 +0900 Subject: [PATCH] Plane: integrate AC_PosControl::get_roll_cd rename --- ArduPlane/quadplane.cpp | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index dbac37f2e0..ee8996d362 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -2530,8 +2530,8 @@ void QuadPlane::vtol_position_controller(void) pos_control->update_xy_controller(); // nav roll and pitch are controller by position controller - plane.nav_roll_cd = pos_control->get_roll(); - plane.nav_pitch_cd = pos_control->get_pitch(); + plane.nav_roll_cd = pos_control->get_roll_cd(); + plane.nav_pitch_cd = pos_control->get_pitch_cd(); /* limit the pitch down with an expanding envelope. This @@ -2597,8 +2597,8 @@ void QuadPlane::vtol_position_controller(void) pos_control->update_xy_controller(); // nav roll and pitch are controller by position controller - plane.nav_roll_cd = pos_control->get_roll(); - plane.nav_pitch_cd = pos_control->get_pitch(); + plane.nav_roll_cd = pos_control->get_roll_cd(); + plane.nav_pitch_cd = pos_control->get_pitch_cd(); // call attitude controller attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(plane.nav_roll_cd, @@ -2735,8 +2735,8 @@ void QuadPlane::takeoff_controller(void) pos_control->update_xy_controller(); // nav roll and pitch are controller by position controller - plane.nav_roll_cd = pos_control->get_roll(); - plane.nav_pitch_cd = pos_control->get_pitch(); + plane.nav_roll_cd = pos_control->get_roll_cd(); + plane.nav_pitch_cd = pos_control->get_pitch_cd(); attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(plane.nav_roll_cd, plane.nav_pitch_cd,