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: fix reset_target_and_rate method #26254

Merged
merged 1 commit into from
Feb 19, 2024

Conversation

IamPete1
Copy link
Member

This method is resetting the euler angle target not the euler rate target. It also only updates the _attitude_target quaternion so the euler is not up to date.

The only users that have reset_rate true are in copter acro while in shut down or ground idle:

case AP_Motors::SpoolState::SHUT_DOWN:
// Motors Stopped
attitude_control->reset_target_and_rate(true);
attitude_control->reset_rate_controller_I_terms();
pilot_desired_throttle = 0.0f;
break;
case AP_Motors::SpoolState::GROUND_IDLE:
// Landed
attitude_control->reset_target_and_rate();
attitude_control->reset_rate_controller_I_terms_smoothly();
pilot_desired_throttle = 0.0f;
break;

@IamPete1 IamPete1 requested a review from lthall February 18, 2024 13:04
Copy link
Contributor

@lthall lthall left a comment

Choose a reason for hiding this comment

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

Nice catch!!

@rmackay9 rmackay9 added the BUG label Feb 18, 2024
@rmackay9
Copy link
Contributor

@IamPete1,

Thanks for this. It's been tested of course?
I've marked this for backporting to 4.5.

@lthall
Copy link
Contributor

lthall commented Feb 18, 2024

This is a difficult thing to test because it doesn't really change anything other than making the code correct.

Both the Euler angle and rates get reset to the quaternion and angular velocity values in the code. I think the only detectable difference will be a single loop where the euler values aren't reset properly.

Thinking about it this probably makes all the attitude target logs correct during ground idle where before they may have been zero. Even that may have already been overridden already though.

@rmackay9 rmackay9 merged commit 6c4c7a2 into ArduPilot:master Feb 19, 2024
92 checks passed
@rmackay9
Copy link
Contributor

OK, in it goes. Thanks!

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
Projects
Status: 4.5.0-beta3
Development

Successfully merging this pull request may close these issues.

3 participants