Browse Source

Copter: AC_ATT correct yaw error calculation

mission-4.1.18
lthall 11 years ago committed by Randy Mackay
parent
commit
329118b7c9
  1. 4
      libraries/AC_AttitudeControl/AC_AttitudeControl.cpp

4
libraries/AC_AttitudeControl/AC_AttitudeControl.cpp

@ -536,8 +536,8 @@ void AC_AttitudeControl::update_rate_bf_targets() @@ -536,8 +536,8 @@ void AC_AttitudeControl::update_rate_bf_targets()
_rate_bf_target.z = constrain_float(_rate_bf_target.z,-_angle_rate_y_max,_angle_rate_y_max);
}
_rate_bf_target.x += -_angle_bf_error.y * _ahrs.get_gyro().z;
_rate_bf_target.y += _angle_bf_error.x * _ahrs.get_gyro().z;
_rate_bf_target.x += _angle_bf_error.y * _ahrs.get_gyro().z;
_rate_bf_target.y += -_angle_bf_error.x * _ahrs.get_gyro().z;
}
//

Loading…
Cancel
Save