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

Adds support for hydrodynamic cross terms #1784

Merged
merged 4 commits into from
Nov 14, 2022

Conversation

arjo129
Copy link
Contributor

@arjo129 arjo129 commented Nov 7, 2022

🎉 New feature

Closes #

Summary

The current plugin implementation only supports diagonal parameters. This PR adds support for cross terms in the added mass and the damping matrix.

What this means for existing users of this plugin

Nothing. The plugin should continue to work as expected. Hence the test suite is not changed.

Cross terms

For reference read: Fossen T. "Guidance and Control of Ocean Vehicles".

Fossens equations rely on so called "stability derivatives" in the damping and the added mass terms. These are given by parameters such as <xUU> . What this means is xUU is the Quadratic Damping term (hence the repeated Us along the X axis for a velocity vector along the X axis (U, V, W are used by SNAME (Society of Naval Architects and Marine Engineers) to represent linear velocity along X, Y and Z axis repspectively). Now, in the case of many ocean going vehicles a push along the U (X-direction velocity) may result in translations and rotations in other axis (for instance my boat might yaw to the right). This may seem counter intuitive but fluid-solid interaction is often complex an unintuitive. In previous versions of the plugin, we only supported the parameters along the diagonal of the damping and added mass matrix. While this is often more than sufficient for simple simulations, there are cases where we may like to simulate cross terms. The adding of cross terms now opens up a lot more parameters. For instance, now we will have terms like xQR (quadratic damping in x axis with respect to angular velocity in roll and yaw axis).

Signed-off-by: Arjo Chakravarty arjo@openrobotics.org

Checklist

  • Signed all commits for DCO
  • Added tests
  • Added example and/or tutorial
  • 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 current plugin implementation only supports diagonal parameters. This PR adds support for cross terms in the added mass and the damping matrix.

## What this means for existing users of this plugin

Nothing. The plugin should continue to work as expected. Hence the test suite is not changed.

## Cross terms

For reference read: Fossen T. "Guidance and Control of Ocean Vehicles".

Fossens equations rely on so called "stability derivatives" in the damping and the added mass terms. These are given by parameters such as `<xUU> `. What this means is `xUU` is the Quadratic Damping term (hence the repeated Us along the X axis for a velocity vector along the X axis (U, V, W are used by SNAME (Society of Naval Architects and Marine Engineers) to represent linear velocity along X, Y and Z axis repspectively). Now, in the case of many ocean going vehicles a push along the U (X-direction velocity) may result in translations and rotations in other axis (for instance my boat might yaw to the right). This may seem counter intuitive but fluid-solid interaction is often complex an unintuitive. In previous versions of the plugin, we only supported the parameters along the diagonal of the damping and added mass matrix. While this is often more than sufficient for simple simulations, there are cases where we may like to simulate cross terms. The adding of cross terms now opens up a lot more parameters. For instance, now we will have terms like `xQR` (quadratic damping in x axis with respect to angular velocity in roll and yaw axis).

Signed-off-by: Arjo Chakravarty <arjo@openrobotics.org>
@github-actions github-actions bot added the 🏯 fortress Ignition Fortress label Nov 7, 2022
@arjo129 arjo129 mentioned this pull request Nov 7, 2022
38 tasks
@codecov
Copy link

codecov bot commented Nov 7, 2022

Codecov Report

Merging #1784 (5692ab7) into ign-gazebo6 (3c06d74) will decrease coverage by 0.02%.
The diff coverage is 100.00%.

@@               Coverage Diff               @@
##           ign-gazebo6    #1784      +/-   ##
===============================================
- Coverage        64.61%   64.59%   -0.03%     
===============================================
  Files              321      321              
  Lines            26290    26292       +2     
===============================================
- Hits             16988    16984       -4     
- Misses            9302     9308       +6     
Impacted Files Coverage Δ
src/systems/hydrodynamics/Hydrodynamics.cc 88.15% <100.00%> (-0.38%) ⬇️
src/systems/rf_comms/RFComms.cc 85.49% <0.00%> (-4.02%) ⬇️

Help us with your feedback. Take ten seconds to tell us how you rate us. Have a feature suggestion? Share it here.

@azeey azeey added MBARI buoy Sponsored by MBARI buoy sim project: https://github.com/osrf/buoy_sim MBARI-LRAUV Sponsored by MBARI-LRAUV project: https://github.com/osrf/lrauv and removed MBARI buoy Sponsored by MBARI buoy sim project: https://github.com/osrf/buoy_sim labels Nov 7, 2022
@azeey azeey requested a review from caguero November 7, 2022 19:42
@caguero caguero requested review from hidmic and removed request for caguero November 7, 2022 19:44
Signed-off-by: Arjo Chakravarty <arjo@openrobotics.org>
src/systems/hydrodynamics/Hydrodynamics.cc Outdated Show resolved Hide resolved
src/systems/hydrodynamics/Hydrodynamics.cc Outdated Show resolved Hide resolved
src/systems/hydrodynamics/Hydrodynamics.cc Outdated Show resolved Hide resolved
src/systems/hydrodynamics/Hydrodynamics.hh Show resolved Hide resolved
Comment on lines +358 to +377
// Damping forces
for(int i = 0; i < 6; i++)
{
for(int j = 0; j < 6; j++)
{
auto coeff = - this->dataPtr->stabilityLinearTerms[i * 6 + j];
for(int k = 0; k < 6; k++)
{
auto index = i * 36 + j * 6 + k;
auto absCoeff =
this->dataPtr->stabilityQuadraticAbsDerivative[index] * abs(state(k));
coeff -= absCoeff;
auto velCoeff =
this->dataPtr->stabilityQuadraticDerivative[index] * state(k);
coeff -= velCoeff;
}

Dmat(i, j) = coeff;
}
}
Copy link
Contributor

@hidmic hidmic Nov 10, 2022

Choose a reason for hiding this comment

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

@arjo129 meta: I'll start by saying I know next to nothing about underwater vessel modelling. That said, I can't relate these equations to those in Fossen's books (ie. Guidance of Ocean Vehicles and Marine Control Systems). I see you are including all cross terms, but none of the models proposed includes a pure quadratic term nor the means to estimate most of the rest (which begs the question, why bother?).

Mind to explain?

Copy link
Contributor Author

@arjo129 arjo129 Nov 14, 2022

Choose a reason for hiding this comment

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

So the LRAUV's original model does, we had not implemented it as we were interested in getting the hydrodynamics plugin up and running early on. It is often hard to estimate and verify the cross terms in comparison to the diagonal terms, however there are definitely techniques that can be used. But yes, if you don't have a team dedicated for fluid dynamics the diagonal terms often are all that is needed.

Signed-off-by: Arjo Chakravarty <arjo@openrobotics.org>
Signed-off-by: Arjo Chakravarty <arjo@openrobotics.org>
@arjo129
Copy link
Contributor Author

arjo129 commented Nov 14, 2022

Test failures seem unrelated.

Copy link
Contributor

@hidmic hidmic left a comment

Choose a reason for hiding this comment

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

LGTM, though CI is a mess right now.

@arjo129 arjo129 merged commit 713516d into ign-gazebo6 Nov 14, 2022
@arjo129 arjo129 deleted the arjo/feat/hydro_cross_terms branch November 14, 2022 23:41
arjo129 added a commit that referenced this pull request Nov 15, 2022
* Adds support for hydrodynamic cross terms

The current plugin implementation only supports diagonal parameters. This PR adds support for cross terms in the added mass and the damping matrix.

Nothing. The plugin should continue to work as expected. Hence the test suite is not changed.

For reference read: Fossen T. "Guidance and Control of Ocean Vehicles".

Fossens equations rely on so called "stability derivatives" in the damping and the added mass terms. These are given by parameters such as `<xUU> `. What this means is `xUU` is the Quadratic Damping term (hence the repeated Us along the X axis for a velocity vector along the X axis (U, V, W are used by SNAME (Society of Naval Architects and Marine Engineers) to represent linear velocity along X, Y and Z axis repspectively). Now, in the case of many ocean going vehicles a push along the U (X-direction velocity) may result in translations and rotations in other axis (for instance my boat might yaw to the right). This may seem counter intuitive but fluid-solid interaction is often complex an unintuitive. In previous versions of the plugin, we only supported the parameters along the diagonal of the damping and added mass matrix. While this is often more than sufficient for simple simulations, there are cases where we may like to simulate cross terms. The adding of cross terms now opens up a lot more parameters. For instance, now we will have terms like `xQR` (quadratic damping in x axis with respect to angular velocity in roll and yaw axis).

Signed-off-by: Arjo Chakravarty <arjo@openrobotics.org>
@azeey
Copy link
Contributor

azeey commented Feb 8, 2023

@arjo129 looks like this PR has changed the behavior of the Hydrodynamics plugin as mentioned in #1871 (comment). Is that a regression or the intended outcome?

@srmainwaring
Copy link
Contributor

looks like this PR has changed the behavior of the Hydrodynamics plugin

Although it's a change to previous behaviour I think the new parameter labels more accurately describe the implementation. For the case in #1871 we've updated the parameters labels in the ROV to use the new definitions and everything is working fine.

It may be a case of adding a note to emphasise that it's a breaking change and provide a pointer to the type of error you might see if you don't update the params (the rapid increase in force causing the collision box to overflow tends to lead you on a wild goose chase initially!).

@azeey
Copy link
Contributor

azeey commented Feb 8, 2023

FYI, another affected user https://answers.gazebosim.org/question/28783/help-with-hydrodynamics-plugin-in-gazebosim-garden/. I'll refer them to this PR.

@arjo129
Copy link
Contributor Author

arjo129 commented Feb 8, 2023

Thanks for Pointing this out @azeey. I dont think behavior change was intended, especially since we didnt update the example. As @srmainwaring pointed out these new names are definitely more sensible. I can add support back for the old names with a warning. I will update the documentation to recommend the new abs names. I don't see the use of Xuu anywhere in the textbook in the way I have written it here. We should probably deprecate Xuu.

arjo129 pushed a commit that referenced this pull request Feb 9, 2023
The PR in #1784 claimed not to introduce behaviour changes,
but actually ended up introducing behaviour changes. Specifically,
it would break a lot of marine simulation code that runs on our tools.
The issue in question is a matter of naming parameters. In the past
`<xUU>` used to refer to the quadratic drag term in the diagonal axis.
This term would be multiplied by the absolute velocity. After #1784 this term
was multiplied by the velocity (no absolute). An equivalent term of `<xUabsU>`
This behaviour change likely breaks all previous maritime simulations that rely on our hydrodynamics plugin.

There are several options:
1. Revert #1784
2. Make `<xUU>` mirror `<xUabsU>`
3. Document the change and mark it as breaking.

This PR goes with option 3 as there are already code bases using `<xUabsU>` nota
tion instead of `<xUU>`. We also add a warning if someone does use the `<xUU>`
term that points to this PR for details.

Signed-off-by: Arjo Chakravarty <“arjoc@google.com”>
arjo129 pushed a commit that referenced this pull request Feb 9, 2023
The PR in #1784 claimed not to introduce behaviour changes,
but actually ended up introducing behaviour changes. Specifically,
it would break a lot of marine simulation code that runs on our tools.
The issue in question is a matter of naming parameters. In the past
`<xUU>` used to refer to the quadratic drag term in the diagonal axis.
This term would be multiplied by the absolute velocity. After #1784 this term
was multiplied by the velocity (no absolute). An equivalent term of `<xUabsU>`
This behaviour change likely breaks all previous maritime simulations that rely on our hydrodynamics plugin.

There are several options:
1. Revert #1784
2. Make `<xUU>` mirror `<xUabsU>`
3. Document the change and mark it as breaking.

This PR goes with option 3 as there are already code bases using `<xUabsU>` nota
tion instead of `<xUU>`. We also add a warning if someone does use the `<xUU>`
term that points to this PR for details.

Signed-off-by: Arjo Chakravarty <arjoc@intrinsic.ai>
arjo129 pushed a commit that referenced this pull request Feb 17, 2023
The PR in #1784 claimed not to introduce behaviour changes,
but actually ended up introducing behaviour changes. Specifically,
it would break a lot of marine simulation code that runs on our tools.
The issue in question is a matter of naming parameters. In the past
`<xUU>` used to refer to the quadratic drag term in the diagonal axis.
This term would be multiplied by the absolute velocity. After #1784 this term
was multiplied by the velocity (no absolute). An equivalent term of `<xUabsU>`
This behaviour change likely breaks all previous maritime simulations that rely on our hydrodynamics plugin.

There are several options:
1. Revert #1784
2. Make `<xUU>` mirror `<xUabsU>`
3. Document the change and mark it as breaking.

This PR goes with option 3 as there are already code bases using `<xUabsU>` nota
tion instead of `<xUU>`. We also add a warning if someone does use the `<xUU>`
term that points to this PR for details.

Signed-off-by: Arjo Chakravarty <arjoc@intrinsic.ai>
arjo129 added a commit that referenced this pull request Feb 18, 2023
* Document behaviour changes introduced #1784

The PR in #1784 claimed not to introduce behaviour changes,
but actually ended up introducing behaviour changes. Specifically,
it would break a lot of marine simulation code that runs on our tools.
The issue in question is a matter of naming parameters. In the past
`<xUU>` used to refer to the quadratic drag term in the diagonal axis.
This term would be multiplied by the absolute velocity. After #1784 this term
was multiplied by the velocity (no absolute). An equivalent term of `<xUabsU>`
This behaviour change likely breaks all previous maritime simulations that rely on our hydrodynamics plugin.

There are several options:
1. Revert #1784
2. Make `<xUU>` mirror `<xUabsU>`
3. Document the change and mark it as breaking.

This PR goes with option 3 as there are already code bases using `<xUabsU>` nota
tion instead of `<xUU>`. We also add a warning if someone does use the `<xUU>`
term that points to this PR for details.

Signed-off-by: Arjo Chakravarty <arjoc@intrinsic.ai>
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
🏯 fortress Ignition Fortress MBARI-LRAUV Sponsored by MBARI-LRAUV project: https://github.com/osrf/lrauv
Projects
Archived in project
Development

Successfully merging this pull request may close these issues.

4 participants