Plane: quad plane uses rate-control control during transitions

This commit is contained in:
Leonard Hall 2018-03-09 18:48:55 +09:00 committed by Randy Mackay
parent c53ba22daa
commit ee745d2cd2
1 changed files with 1 additions and 1 deletions

View File

@ -675,7 +675,7 @@ void QuadPlane::multicopter_attitude_rate_update(float yaw_rate_cds)
// use the fixed wing desired rates // use the fixed wing desired rates
float roll_rate = plane.rollController.get_pid_info().desired; float roll_rate = plane.rollController.get_pid_info().desired;
float pitch_rate = plane.pitchController.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);
} }
} }