Skip to content
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

AC_AttitudeControl: Add function to limit target attitude thrust angle #28316

Open
wants to merge 1 commit into
base: master
Choose a base branch
from

Conversation

lthall
Copy link
Contributor

@lthall lthall commented Oct 5, 2024

This PR provides a feature for use in plane to limit the maximum target angle.

When the target angle is above a given value the current attitude is used to determine the minimum rotation vector back to within the allowable lean angle using only roll and pitch.

libraries/AC_AttitudeControl/AC_AttitudeControl.cpp Outdated Show resolved Hide resolved
Quaternion attitude_body;
_ahrs.get_quat_body_to_ned(attitude_body);

Vector3f gyro = _ahrs.get_gyro_latest();
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Should we be using the new _rate_gyro variable that was recently added?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I believe so.

@lthall lthall force-pushed the 20241003_AttitudeControl_Angle_Limit branch from 5bfb7ee to 1f501fc Compare October 6, 2024 01:03
}

// the cross product of the current thrust vector and vertical thrust vector defines the rotation vector
Vector3f thrust_vec_cross = thrust_vec % thrust_vector_up;
Copy link
Contributor

@priseborough priseborough Oct 7, 2024

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Can you confirm that this vector is intended to be the target rotation vector to get back to upright?

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

OK, I figured it out. The subsequent usage is consistent with that definition.

attitude_target_offset.from_axis_angle(thrust_vec_cross, thrust_correction_angle);
_attitude_target = attitude_target_offset * attitude_body;

// Set angular velocity targets when further than 1.25 * thrust_angle_max_cd
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Based on my reading of this code this would be more accurately described as:

// Angular velocity targets must be zeroed at large thrust angles to prevent them from preventing efficient recovery
// so zero angular velocity targets when tilted more than 1.25 * thrust_angle_max_cd
// Interpolate between an unmodified ang_vel_target at thrust_angle_max and zero at 1.25 * thrust_angle_max
// This ensures small angles past thrust_angle_max_cd do not zero angular velocity targets and prevent full recovery

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

Successfully merging this pull request may close these issues.

3 participants