mirror of https://github.com/ArduPilot/ardupilot
Plane: integrate AC_PosControl::get_roll_cd rename
This commit is contained in:
parent
74d22594db
commit
ff2ae1d7d1
|
@ -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,
|
||||
|
|
Loading…
Reference in New Issue