-
Notifications
You must be signed in to change notification settings - Fork 375
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
Instant change in joint angles when using PxArticulationReducedCoordinate. #204
Comments
Hello NVidia, After debugging the phenomena for a moment it feels that the problem lays in multiplying a quaternion by a very close to it inverted quaternion in two places in /physx/source/lowleveldynamics/src/DyFeatherstoneForwardDynamic.cpp. It feels that due to finite float32 data type precision sometimes the result instead of being close to (x=0, y=0, z=0, w=1) happens to become close to (x=0, y=0, z=0, w=-1). The suggestion is instead of
do
It looks like it fixes the problem. Please find the patch for "105.1-physx-5.3.0" tag pasted below.
|
Hi @z80 Please re-open the issue if it still persists after applying the changes. |
Hello @jcarius-nv Thank you so much for the reference to #140. I'd like to clarify that #140 is already in place in the code and the issue persists. Per my understanding, the fix proposed in #140 might not be enough and when it is applied, math explosions still happen. The math in #140 in both DyFeatherstoneForwardDynamic.cpp and DyFeatherstoneArticulation.cpp checks "if delta > 180, make delta=360-delta". It feels that w<0.f may be a valid solution depending on what exactly the two quaternions are. Due to that, it feels that more correct check would be "if ((both are < 180 or both are > 180) and delta is still > 180), make delta=360-delta". In other words, instead of
do this
Thank you! |
ok, interesting to hear. Can you share some numeric values where this extended check is needed and where the simpler one that I proposed is doing the wrong thing? The two places I touched in issue #140 had the quaternion converted to the angle-axis representation afterwards. If you have an example where the angle-axis is still screwed up (abs(angle) > pi) that would be great. Also, I'm wondering why you write "if delta > 180, make delta=360-delta". I'd argue that angle x and angle 360-x are not the same, rather something like
|
Hello @jcarius-nv, Thank you for the reply! Please find the information below.
-cos(x/2)=cos(180+x/2) and -sin(x/2)axis=sin(180+x/2)axis, which gives x->x+360, axis->axis, -cos(x/2)=cos(x/2-180) and -sin(x/2)axis=sin(x/2-180)axis, which gives x->x-360, axis->axis, -cos(x/2)=cos(180-x/2) and -sin(x/2)axis=sin(180-x/2)(-axis), which gives x->360-x, axis->-axis. In my "delta=360-delta" for brevity I referred to just the 3-d case. If I understand correctly, you refer to the first two cases when you say "delta=delta-360", "delta=delta+360" based on the knowledge of what's happening with the joint.
The proposed modification "if ( (newParentToChild.w * relativeQuat.w) < 0.f ) ..." only makes the example code provided not produce instant joint coordinate changes. But further testing has shown that the proposed patch doesn't make all possible articulations work with TGS. It feels that there is more to that problem. Thank you! |
Internal Tracking: PX-4530 |
Thank you for the clarification, indeed there are multiple ways how to change the quaternion without actually changing the underlying rotation. I tested again with the latest version and could no longer see a jump in joint angles with your example, i.e., it prints
I'd propose to close this thicket for now because your example appears to be ok. Please create a new ticket if you can reproduce further issues of joints flipping their positions unexpectedly. |
Hello!
I'm working with PxArticulationGeneralizedCoordinate. No forces are applied, gravity is zero, no collisions are created. Some of the joint angles instantly change after a single scene->simulate() call. I've tested several PhysX versions: PhysX 4, PhysX 5.1.3 and PhysX 5.3.0 on Windows 10 and Ubuntu Linux 18.04. The behavior is identical in all of them.
The issue happens only with a specific armature topology provided in the snippet code below and works as expected with different topologies.
All links have mass of 1kg and identity inertia matrix. All joints are either eSPHERICAL or eREVOLUTE. No control is applied. I expect all angles to remain zero. But angles 17, 18, 19 change instantly. Please see the example application attached (for PhysX 5.1.3) and the result output "image.png".
Thank you!
Library and Version
PhysX v5.1.3
Operating System
Windows 10, Ubuntu Linux 18.04.
Steps to Trigger Behavior
Code Snippet to Reproduce Behavior
Expected Behavior
When created, all joint angles are zero.
Environment takes a single time step of dt=1.0/240.0 seconds.
Due to no forces are applied, gravity is zero, no collision volumes are created, and due to all mass and inertia are assigned to be 1, it is expected that all joint angles remain exactly zero or be negligibly small.
Actual Behavior
After a single call to scene->simulate( 1.0/240.0 )
and reading articulation->copyInternalStateToCache( *cache, physx::PxArticulationCacheFlag::ePOSITION | physx::PxArticulationCacheFlag::eVELOCITY );
cache->jontPosition[17] is -5.43, cache->jontPosition[18] is 3.11, cache->jontPosition[19] is -0.6.
The text was updated successfully, but these errors were encountered: