AC_AttControl: bug fix to yaw rate limit

This commit is contained in:
Randy Mackay 2014-02-09 16:02:13 +09:00 committed by Andrew Tridgell
parent 6380a39d3a
commit 5f89e9e746
1 changed files with 1 additions and 1 deletions

View File

@ -192,7 +192,7 @@ void AC_AttitudeControl::angle_to_rate_ef_yaw()
// constrain rate request
if (_flags.limit_angle_to_rate_request) {
_rate_ef_target.y = constrain_float(_rate_ef_target.y,-_angle_rate_y_max,_angle_rate_y_max);
_rate_ef_target.z = constrain_float(_rate_ef_target.z,-_angle_rate_y_max,_angle_rate_y_max);
}
// To-Do: deal with trad helicopter which do not use yaw rate controllers if using external gyros