Plane: integrate AC_PosControl::get_roll_cd rename

This commit is contained in:
Leonard Hall 2021-05-12 13:32:42 +09:00 committed by Andrew Tridgell
parent 74d22594db
commit ff2ae1d7d1
1 changed files with 6 additions and 6 deletions

View File

@ -2530,8 +2530,8 @@ void QuadPlane::vtol_position_controller(void)
pos_control->update_xy_controller(); pos_control->update_xy_controller();
// nav roll and pitch are controller by position controller // nav roll and pitch are controller by position controller
plane.nav_roll_cd = pos_control->get_roll(); plane.nav_roll_cd = pos_control->get_roll_cd();
plane.nav_pitch_cd = pos_control->get_pitch(); plane.nav_pitch_cd = pos_control->get_pitch_cd();
/* /*
limit the pitch down with an expanding envelope. This limit the pitch down with an expanding envelope. This
@ -2597,8 +2597,8 @@ void QuadPlane::vtol_position_controller(void)
pos_control->update_xy_controller(); pos_control->update_xy_controller();
// nav roll and pitch are controller by position controller // nav roll and pitch are controller by position controller
plane.nav_roll_cd = pos_control->get_roll(); plane.nav_roll_cd = pos_control->get_roll_cd();
plane.nav_pitch_cd = pos_control->get_pitch(); plane.nav_pitch_cd = pos_control->get_pitch_cd();
// call attitude controller // call attitude controller
attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(plane.nav_roll_cd, 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(); pos_control->update_xy_controller();
// nav roll and pitch are controller by position controller // nav roll and pitch are controller by position controller
plane.nav_roll_cd = pos_control->get_roll(); plane.nav_roll_cd = pos_control->get_roll_cd();
plane.nav_pitch_cd = pos_control->get_pitch(); plane.nav_pitch_cd = pos_control->get_pitch_cd();
attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(plane.nav_roll_cd, attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(plane.nav_roll_cd,
plane.nav_pitch_cd, plane.nav_pitch_cd,