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

Revert to use of cos^2 in LiftDrag plugin #2273

Merged
merged 5 commits into from
Jan 8, 2024

Conversation

arjo129
Copy link
Contributor

@arjo129 arjo129 commented Dec 27, 2023

🦟 Bug fix

Fixes #

Summary

In response to #2189 (comment)

As suggested by @srmainwaring I also renamed cosSweepAngle ->
cos2SweepAngle to prevent further confusion.

Checklist

  • Signed all commits for DCO
  • Added tests
  • Updated documentation (as needed)
  • Updated migration guide (as needed)
  • Consider updating Python bindings (if the library has them)
  • codecheck passed (See contributing)
  • All tests passed (See test coverage)
  • While waiting for a review on your PR, please help review another open pull request to support the maintainers

Note to maintainers: Remember to use Squash-Merge and edit the commit message to match the pull request summary while retaining Signed-off-by messages.

The changes in #2189 have caused a regression for our upstream users.
This fix disables moment calculations by defaulting Cma to zero. It
should help mitigate some of the regression. There is also an [ongoing
discussion](#2189 (comment)) as to whether the cos term should be cos^2 or cos.

Signed-off-by: Arjo Chakravarty <[email protected]>
In response to #2189 (comment)

As suggested by @srmainwaring I also renamed cosSweepAngle ->
cos2SweepAngle to prevent further confusion.

Signed-off-by: Arjo Chakravarty <[email protected]>
Copy link

codecov bot commented Dec 27, 2023

Codecov Report

Attention: 3 lines in your changes are missing coverage. Please review.

Comparison is base (8ec622d) 64.74% compared to head (71dcdb8) 64.72%.
Report is 1 commits behind head on gz-sim7.

Files Patch % Lines
src/systems/lift_drag/LiftDrag.cc 57.14% 3 Missing ⚠️
Additional details and impacted files
@@             Coverage Diff             @@
##           gz-sim7    #2273      +/-   ##
===========================================
- Coverage    64.74%   64.72%   -0.03%     
===========================================
  Files          357      357              
  Lines        29141    29139       -2     
===========================================
- Hits         18868    18860       -8     
- Misses       10273    10279       +6     

☔ View full report in Codecov by Sentry.
📢 Have feedback on the report? Share it here.

Base automatically changed from arjo/feat/disable_moments_by_default to gz-sim7 December 27, 2023 07:17
@bperseghetti
Copy link
Member

Looks like it needs a rebase and a commit squash to the 3 lines changed from cos->cos2.

@arjo129
Copy link
Contributor Author

arjo129 commented Dec 28, 2023

Looks like it needs a rebase and a commit squash to the 3 lines changed from cos->cos2.

It's OK theres no need to do anything since we squash and rebase before we merge into main in anycase.

Copy link
Contributor

@srmainwaring srmainwaring left a comment

Choose a reason for hiding this comment

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

LGTM. Suggested more detail in the comment to explain origin of formula.

Co-authored-by: Rhys Mainwaring <[email protected]>
Signed-off-by: Arjo Chakravarty <[email protected]>
Copy link
Contributor

@azeey azeey left a comment

Choose a reason for hiding this comment

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

I ported the Gazebo-classic LiftDrag to gz-sim, but I mostly copied the existing code. I didn't find any references for the equations used.

@@ -327,8 +327,9 @@ void LiftDragPrivate::Update(EntityComponentManager &_ecm)
double sinSweepAngle = math::clamp(
spanwiseI.Dot(velI), minRatio, maxRatio);

// get cos from trig identity
double cosSweepAngle = sqrt(1.0 - sinSweepAngle * sinSweepAngle);
// The sweep adjustment depends on the velocity component normal to the wing leading
Copy link
Contributor

Choose a reason for hiding this comment

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

linter seems unhappy about these lines.

double cosSweepAngle = sqrt(1.0 - sinSweepAngle * sinSweepAngle);
// The sweep adjustment depends on the velocity component normal to the wing leading
// edge which appears quadratically in the dynamic pressure, so scale by cos^2 .
double cos2SweepAngle = 1.0 - sinSweepAngle * sinSweepAngle;
Copy link
Contributor

Choose a reason for hiding this comment

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

@frede791 will this break your models?

Copy link
Member

Choose a reason for hiding this comment

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

No, shouldn't be an issue for the PX4 models.

Copy link
Contributor

Choose a reason for hiding this comment

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

No this is fine.

Signed-off-by: Arjo Chakravarty <[email protected]>
@mjcarroll mjcarroll merged commit 2bba478 into gz-sim7 Jan 8, 2024
9 of 11 checks passed
@mjcarroll mjcarroll deleted the arjo/feat/revert_cos2_changes branch January 8, 2024 14:40
@scpeters scpeters mentioned this pull request Jan 17, 2024
7 tasks
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
Archived in project
Development

Successfully merging this pull request may close these issues.

6 participants