Browse Source

Plane: quad plane uses rate-control control during transitions

master
Leonard Hall 7 years ago committed by Randy Mackay
parent
commit
ee745d2cd2
  1. 2
      ArduPlane/quadplane.cpp

2
ArduPlane/quadplane.cpp

@ -675,7 +675,7 @@ void QuadPlane::multicopter_attitude_rate_update(float yaw_rate_cds) @@ -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);
}
}

Loading…
Cancel
Save