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

Update rotation computation #319

Open
wants to merge 6 commits into
base: update-0.3.3
Choose a base branch
from

Conversation

nmnaughton
Copy link
Collaborator

I was working on some simulations using relatively stiff rods and was having stability issues. I tracked it down to how the rotation is computed. Numerical error can cause the trace of the directors to be slightly larger than the max value of 3, which then yields a NaN when arccos is called.

The previous solution was to subtract 1e-10 to account for this occasional numerical error, but for a stiff rod, this adjustment was not always enough. Clipping the trace to -3 and 3, which corresponds to the allowable range of arccos yielded large improvements in stability with minimal performance penalty.

Make sure that arccos is never given a value outside of its allowable range. The previous version would occasionally yield a nan for stiff rods.
@codecov-commenter
Copy link

codecov-commenter commented Jan 5, 2024

Codecov Report

All modified and coverable lines are covered by tests ✅

Comparison is base (93441ed) 87.78% compared to head (8ac9c63) 87.78%.
Report is 218 commits behind head on update-0.3.2.

❗ Current head 8ac9c63 differs from pull request most recent head f6a761b. Consider uploading reports for the commit f6a761b to get more accurate results

❗ Your organization needs to install the Codecov GitHub app to enable full functionality.

Additional details and impacted files
@@              Coverage Diff              @@
##           update-0.3.2     #319   +/-   ##
=============================================
  Coverage         87.78%   87.78%           
=============================================
  Files                43       43           
  Lines              2938     2940    +2     
  Branches            341      341           
=============================================
+ Hits               2579     2581    +2     
  Misses              335      335           
  Partials             24       24           

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

@skim0119 skim0119 changed the base branch from master to update-0.3.2 January 5, 2024 14:30
elastica/_rotations.py Outdated Show resolved Hide resolved
Co-authored-by: Seung Hyun Kim <[email protected]>
@armantekinalp armantekinalp requested review from Ali-7800 and sy-cui and removed request for bhosale2 January 6, 2024 12:21
Copy link
Contributor

@sy-cui sy-cui left a comment

Choose a reason for hiding this comment

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

One minor change.

elastica/_rotations.py Outdated Show resolved Hide resolved
elastica/_rotations.py Show resolved Hide resolved
Copy link
Collaborator

@skim0119 skim0119 left a comment

Choose a reason for hiding this comment

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

My concern is that it will now pass all the "actual" instability cases. Wouldn't it be better to make this threshold to be adjustable? I think clipping is a little too extreme, and actually a wrong implementation. It can cause more ghost issues without showing user where the problem is coming from.

@nmnaughton
Copy link
Collaborator Author

What do you mean by instability? This is clipping the trace of the directors product. If the directors are sufficiently orthonormal, then this is just a floating point issue for vector representation of small angles. This issue will only occur when neighboring directors are very close to each other (Tr(R) ~= 3 means no rotation), so I don't see it as stability issue per se.

@skim0119
Copy link
Collaborator

skim0119 commented Jan 8, 2024

I mean instable as when position and directors start to explode and become not orthogonal and misaligned. Getting an error from this function was one of the early indicator, but now it will just pass with clipped trace.

What we wanted is something like

if trace < 3.0 + threshold:
    theta = arccos(0.5 * trace - 0.5)
else:
    raise Error

which became the current form of implementation theta = arccos(0.5 * trace - 0.5 - threshold) due to numba optimization. We want to allow threshold amount of band to accommodate for upstream numerical accuracy, but I'm not sure allowing all theta > 3 values to pass is a good idea.

How about either

  • Use min/max implementation as above but add exception/warning message if trace deviates threshold amount. I think now numba does have some exception handling capability with python.
  • Keep previous implementation but make threshold configurable by user.
  • [Little far-fetched] Add re-orthogonalization step on directors before stepping, so we can make sure we don't have numerical issue in this function.

Copy link
Collaborator

@Ali-7800 Ali-7800 left a comment

Choose a reason for hiding this comment

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

I don't think the poetry.lock needs to be changed here, right @armantekinalp?

@nmnaughton
Copy link
Collaborator Author

A few thoughts.

  1. Do the directors become non-orthonormal during instability? I usually pay attention to the positions to determine stability/blowup.
  2. The simulation does not stop when this returns a NaN, it just continues computing on NaNs, so why does it matter if instability is "caught" here? If the simulation is going to blow up, it will do that regardless, while sometimes it might be able to recover (though again, I am doubtful that trace > 3.0 is related to anything other than round off accumulation). Non-orthonormal vectors do not necessarily have a trace > 3, so this doesn't really test for orthonormality.
  3. The current approach introduces error at every step. Trace = 3.0 means no rotation, so at rest, the rod will always be trying to rotate slightly proportional to the threshold amount.
  4. I have verified that the cases this was causing problems for me appear to be round off accumulation. For example, two neighboring elements with the normals [-3.69221646e-05 9.99999999e-01 0.00000000e+00] and [-3.93231655e-05 9.99999999e-01 0.00000000e+00] will fail at the current threshold.
  5. When I reran the same simulation that gave me these directors using this PR, I stayed below the current threshold (1e-10) for all cases (in fact, it stayed below 1e-11). My interpretation is that since all rotations are no longer being biased by the threshold amount, the round-off error does not accumulate to the same degree, so clipping may in fact be more stable and accurate.

@skim0119
Copy link
Collaborator

skim0119 commented Jan 16, 2024

A few thoughts.

  1. Do the directors become non-orthonormal during instability? I usually pay attention to the positions to determine stability/blowup.
  2. The simulation does not stop when this returns a NaN, it just continues computing on NaNs, so why does it matter if instability is "caught" here? If the simulation is going to blow up, it will do that regardless, while sometimes it might be able to recover (though again, I am doubtful that trace > 3.0 is related to anything other than round off accumulation). Non-orthonormal vectors do not necessarily have a trace > 3, so this doesn't really test for orthonormality.
  3. The current approach introduces error at every step. Trace = 3.0 means no rotation, so at rest, the rod will always be trying to rotate slightly proportional to the threshold amount.
  4. I have verified that the cases this was causing problems for me appear to be round off accumulation. For example, two neighboring elements with the normals [-3.69221646e-05 9.99999999e-01 0.00000000e+00] and [-3.93231655e-05 9.99999999e-01 0.00000000e+00] will fail at the current threshold.
  5. When I reran the same simulation that gave me these directors using this PR, I stayed below the current threshold (1e-10) for all cases (in fact, it stayed below 1e-11). My interpretation is that since all rotations are no longer being biased by the threshold amount, the round-off error does not accumulate to the same degree, so clipping may in fact be more stable and accurate.

I agree with most of your point. 3), I checked some time ago that the threshold amount of error we are adding here is negligible compare to other numerical issues upstream (especially multiplying moduli to shear), but I think it is case dependent.

I think we are somewhat on the same page: in most of the case when simulation is running properly, this corner case shouldn't be an issue. I am just having a perspective that the behavior of a code block, especially if it is a free-function, should only depend on its functionality. Basically, I think producing NaN is more expected behavior, especially when the input directors are some instable directors. In this regard, I agree with your changes, just we should clearly state and document this behavior inside the function, and maybe add warning message if the trace is significantly deviated outside (-1,3) bound (I think this will benefit many other cases to find numerical issues). If you agree, I can make a change and commit. I can also write some test for the cases, and address the threshold inside the sin function.

Copy link
Collaborator

@bhosale2 bhosale2 left a comment

Choose a reason for hiding this comment

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

Besides resolving the major point raised by @skim0119, minor changes.

Comment on lines -150 to +153
theta = arccos(0.5 * trace - 0.5 - 1e-10)
# Clip the trace to between -1 and 3.
# Any deviation beyond this is numerical error
trace = min(trace, 3.0)
trace = max(trace, -1.0)
theta = arccos(0.5 * trace - 0.5)
Copy link
Collaborator

Choose a reason for hiding this comment

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

do we have some quantification for our reference regarding the performance penalty this change creates?

poetry.lock Outdated
@@ -1,10 +1,9 @@
# This file is automatically @generated by Poetry and should not be changed by hand.
# This file is automatically @generated by Poetry 1.6.1 and should not be changed by hand.
Copy link
Collaborator

Choose a reason for hiding this comment

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

there shouldn't be any change in this file right as @Ali-7800 pointed out

@armantekinalp armantekinalp changed the base branch from update-0.3.2 to master March 11, 2024 22:55
@skim0119 skim0119 changed the base branch from master to update-0.3.3 March 26, 2024 20:27
@bhosale2
Copy link
Collaborator

bhosale2 commented May 7, 2024

@skim0119 and @armantekinalp what should be the follow up on this one?

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.

6 participants