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

Fix trlog exceptional condition #63

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

Conversation

elton-choi
Copy link

For the rotation part of trlog, the iseye condition does not catch all conditions where the rotation value is near-zero. I actually got divided-by-zero exception in the general case part while doing some simulation.

There are many ways to avoid divided-by-zero exception when we calculate skw = ... / math.sin(theta). But, I recommend you to fix iseye routine.
Instead of iseye routine, we can simply check if trace(R) = 1 + 2cos(theta=0) = 3

For the rotation part of trlog, the iseye condition does not catch all conditions where the rotation value is near-zero.
I actually got divided-by-zero exception in the general case part while doing some simulation.

There are many ways to avoid divided-by-zero exception when we calculate skw = ... / math.sin(theta).
But, I recommend you to fix iseye routine.
Instead of iseye routine, we can simply check if trace(R) = 1 + 2cos(theta=0) = 3
@petercorke
Copy link
Collaborator

thanks for this, it's elegant to use the trace twice. Can you give me the numeric example where iseye() failed. iseye() applies the tolerance threshold to the norm of the matrix, rather than the trace, and the latter is bigger than the former so the tolerances are not equivalent.

On the typing branch I've updated iseye and added a unit test for trlog for this case.

Perhaps there should be a test on sin(theta) in the "general case" to truly ensure that you're example can't happen again.

@@ -1221,13 +1221,14 @@ def trlog(T, check=True, twist=False, tol=10):
elif isrot(T, check=check):
# deal with rotation matrix
R = T
if smb.iseye(R):
trace_R = np.trace(R)
if abs(trace_R - 3) < tol * _eps:
# matrix is identity
if twist:

Choose a reason for hiding this comment

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

nit: write

return np.zeros((3,)) if twist else np.zeros((3, 3)

it is much simpler to read and less lines

sorry has nothing to do with the PR :-)

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