mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
AC_AttControl: rate compensation for yaw
This commit is contained in:
parent
0d87298221
commit
922026c15c
@ -471,6 +471,9 @@ void AC_AttitudeControl::update_rate_bf_targets()
|
||||
if (_flags.limit_angle_to_rate_request) {
|
||||
_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 * _ins.get_gyro().z;
|
||||
_rate_bf_target.y += _angle_bf_error.x * _ins.get_gyro().z;
|
||||
}
|
||||
|
||||
//
|
||||
|
Loading…
Reference in New Issue
Block a user