From ee745d2cd2ed49fa8af2d61da7ffeddb6d15fd78 Mon Sep 17 00:00:00 2001 From: Leonard Hall Date: Fri, 9 Mar 2018 18:48:55 +0900 Subject: [PATCH] Plane: quad plane uses rate-control control during transitions --- ArduPlane/quadplane.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index ba8a40c232..ccaa9010a2 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -675,7 +675,7 @@ void QuadPlane::multicopter_attitude_rate_update(float yaw_rate_cds) // use the fixed wing desired rates float roll_rate = plane.rollController.get_pid_info().desired; float pitch_rate = plane.pitchController.get_pid_info().desired; - attitude_control->input_euler_rate_roll_pitch_yaw(roll_rate*100, pitch_rate*100, yaw_rate_cds); + attitude_control->input_rate_bf_roll_pitch_yaw_2(roll_rate*100.0f, pitch_rate*100.0f, yaw_rate_cds); } }