Skip to content

Yaw rate control issue: large attitude error combined with high yaw rate leads to increasing spin rate (possible control logic flaw) #29756

New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Open
kcx1207 opened this issue Apr 11, 2025 · 11 comments

Comments

@kcx1207
Copy link

kcx1207 commented Apr 11, 2025

Issue details

When flying a traditional helicopter in ALTHOLD mode, if the aircraft experiences a large attitude error (for example, large roll and pitch deviations) and is already spinning at a high yaw rate, the current control logic sets the desired yaw angular velocity (_ang_vel_body.z) equal to the current gyro reading (_ahrs.get_gyro().z).
While this design might be intended to prevent over-control during large attitude errors, in the case of a helicopter already spinning, this behavior leads to the following critical issue:
1.The controller continuously commands the same high yaw rate as the current gyro reading.
2.This causes the yaw rate to increase uncontrollably.
3.Eventually, this leads to complete loss of control and a crash.

I have confirmed:
1.My helicopter’s tail rotor system is mechanically sound.
2.Yaw control works normally under normal conditions.
3.However, when attitude errors become large (e.g., due to disturbances or aggressive maneuvers) and the helicopter enters a spin, this control logic unintentionally sustains or even worsens the spin.

It seems the current control design assumes large attitude error but no existing spin, and tries to maintain current yaw rate to prevent overcorrection.
However, for helicopters, if a spin has already developed, continuing to command the same yaw rate can amplify the spin drastically.

I believe this is a genuine bug in the control logic specific to traditional helicopters.

Additionally, I would like to ask:
1.Could this issue also occur in other flight modes (e.g., Loiter, Stabilize, etc.)?
2.Does the current logic apply universally to all frame types, or is it specific to helicopters?

Version
Copter 4.4. 0

Platform
Copter

Hardware type
Pixhawk

Steps to reproduce
1.Fly a traditional helicopter in ALTHOLD mode.
2.The helicopter begins to spin (high yaw rate).
3.Induce a large attitude error in flight (e.g., forceful pitch or roll angle disturbances).
4.In logs, it can be observed that the expected yaw rate is almost equal to gyro.z.

Code reference

The problematic code is located in:

libraries/AC_AttitudeControl/AC_AttitudeControl.cpp
Function: AC_AttitudeControl::thrust_heading_rotation_rate(...)

Relevant snippet:

if (_thrust_error_angle > AC_ATTITUDE_THRUST_ERROR_ANGLE * 2.0f) {
    _ang_vel_body.z = _ahrs.get_gyro().z;
} else if (_thrust_error_angle > AC_ATTITUDE_THRUST_ERROR_ANGLE) {
    _feedforward_scalar = (1.0f - (_thrust_error_angle - AC_ATTITUDE_THRUST_ERROR_ANGLE) / AC_ATTITUDE_THRUST_ERROR_ANGLE);
    _ang_vel_body.x += ang_vel_body_feedforward.x * _feedforward_scalar;
    _ang_vel_body.y += ang_vel_body_feedforward.y * _feedforward_scalar;
    _ang_vel_body.z = _ahrs.get_gyro().z * (1.0 - _feedforward_scalar) + _ang_vel_body.z * _feedforward_scalar;
} else {
    _ang_vel_body += ang_vel_body_feedforward;
}

logs figure

@kcx1207
Copy link
Author

kcx1207 commented Apr 11, 2025

Image

@kcx1207
Copy link
Author

kcx1207 commented Apr 11, 2025

@rmackay9 @IamPete1

@rmackay9
Copy link
Contributor

Hi @kcx1207,

Thanks for the report. Any chance you could repeat the test to confirm it happens with a more recent version of AP? 4.4 is quite old now. Ideally 4.7.0-dev but 4.6 would likely be sufficient as well, thanks!

@kcx1207
Copy link
Author

kcx1207 commented Apr 12, 2025

Hi @rmackay9

Thank you for your reply!

From Copter 3.4.1, this logic was introduced, and I’ve confirmed that in the latest available version Copter 4.5.7, it is still present. Unfortunately, I couldn't find 4.7.0-dev — could you kindly provide me with a link to that version?

I suspect that when this part of the logic was originally designed, it might not have fully considered the extreme scenario where both the attitude error is large and the helicopter is already spinning. In such cases, directly using the current gyro.z as the desired yaw rate could potentially lead to uncontrollable spin-up.

To address this, I have made the following changes to the source code:

// if (_thrust_error_angle > AC_ATTITUDE_THRUST_ERROR_ANGLE * 2.0f) {
//     ang_vel_body.z = gyro.z;
// } else if (_thrust_error_angle > AC_ATTITUDE_THRUST_ERROR_ANGLE) {
if (_thrust_error_angle > AC_ATTITUDE_THRUST_ERROR_ANGLE) {
    _feedforward_scalar = (1.0f - (_thrust_error_angle - AC_ATTITUDE_THRUST_ERROR_ANGLE) / AC_ATTITUDE_THRUST_ERROR_ANGLE);
    ang_vel_body.x += ang_vel_body_feedforward.x * _feedforward_scalar;
    ang_vel_body.y += ang_vel_body_feedforward.y * _feedforward_scalar;
    ang_vel_body.z += ang_vel_body_feedforward.z;
    // ang_vel_body.z = gyro.z * (1.0 - _feedforward_scalar) + ang_vel_body.z * _feedforward_scalar;
} else {
    ang_vel_body += ang_vel_body_feedforward;
}

With this change, I no longer observe the uncontrollable spin in my tests.
Of course, this is only a temporary workaround for validation — I’m not suggesting it as a final solution.

Could you please help to confirm if this issue still exists in 4.7.0-dev, and whether this logic might need a review?

Thanks a lot for your attention!

Image
Image
Image

@kcx1207
Copy link
Author

kcx1207 commented Apr 18, 2025

@rmackay9

@peterbarker
Copy link
Contributor

From Copter 3.4.1, this logic was introduced, and I’ve confirmed that in the latest available version Copter 4.5.7, it is still present. Unfortunately, I couldn't find 4.7.0-dev — could you kindly provide me with a link to that version?

You can download 4.7.0-dev from https://firmware.ardupilot.org/Copter/latest/

Pinging @bnsgeyer , too, our Heli maintainer.

@bnsgeyer
Copy link
Contributor

bnsgeyer commented May 1, 2025

Pinging @lthall as this is generically the multirotor code. He and I will need to chat about this.

@kcx1207 the attitude errors that you invoke seem unrealistic for a properly tuned aircraft. But Leonard and I will chat about this and review your proposed solution.
Thanks

@lthall
Copy link
Contributor

lthall commented May 1, 2025

Hi @kcx1207,

You are mostly correct with your interpration. I do think the following part isn't completly accurate:

1.The controller continuously commands the same high yaw rate as the current gyro reading.
2.This causes the yaw rate to increase uncontrollably.
3.Eventually, this leads to complete loss of control and a crash.

The purpose of setting the desired yaw angular velocity (_ang_vel_body.z) equal to the current gyro reading (_ahrs.get_gyro().z) is to relax the yaw controller, zeroing the P and D terms. So there is nothing left to cause a further increase in spin rate, much less uncontrolled increase. In fact, the only residual output should be the I term and that should be still opposed to any initial yaw rate.

However, when attitude errors become large (e.g., due to disturbances or aggressive maneuvers)

Disturbances yes but aggressive manuvers should not cause a large atitutde error on a properly setup aircraft.

It seems the current control design assumes large attitude error but no existing spin, and tries to maintain current yaw rate to prevent overcorrection.

This isn't completly correct. When I wrote this the intention was to minimise control output to yaw and instead focus all control power to roll and pitch to bring the atitutde error back under control. Heli is actually one of the airframes that have a seperate yaw actuator and this doesn't have a significant impact on the ability of the aircraft to actuate roll and pitch.

So this isn't a bug but the question remains, does this code have some unintended behaviour in some corner of the flight envelope that we may be able to improve for heli?

There is a lot of information missing from your discription of the problem. It would be helpfull for me to see your log. I assume you are using a simulator of some sort and can reproduce the problem. Could you make sure fast logging is turned on to maximise the data in the log.

Thanks.

@IamPete1
Copy link
Member

IamPete1 commented May 1, 2025

There are some other vehicles where yaw is not coupled to the roll and pitch. Tricopters (technically it is, but only a minor coupling) and other vectoring vehicles, coax copters. We could add a method on motors that could return if the relax should be done.

@lthall
Copy link
Contributor

lthall commented May 1, 2025

There are some other vehicles where yaw is not coupled to the roll and pitch. Tricopters (technically it is, but only a minor coupling) and other vectoring vehicles, coax copters. We could add a method on motors that could return if the relax should be done.

While I dissagree with your assessment of tricopters and coax copters (tricopters coupling isn't minor in my opinion and yaw can half the thrust of coax copters and with it half the athority of roll and pitch), I do agree that this is something we could make a option that a frame can turn on or off. However, before I did that I would like to understand what is happening here as the discription of this problem doesn't seem to match what I expect from the physics. I really need to see a log.

@kcx1207
Copy link
Author

kcx1207 commented May 5, 2025

@peterbarker @bnsgeyer @lthall @IamPete1 Thank you all for your reply, here is the log file link. This error hasn't appeared since I changed the code myself. Hope my experience has been helpful in the development of the project!
https://drive.google.com/file/d/1F7vX8w_ZBS4MSyT6BLwBKApl7L2wcI_O/view?usp=sharing

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

No branches or pull requests

6 participants