FeatherstoneArticulation::setupInternalConstraintsRecursive segfault when using an articulation with more than 255 links. #417
Replies: 2 comments
-
Found the culprit : Line 339 of
nbLinks is casted to a 8bit uint in mLinkCount, so if it's greater than 255 it causes an integer overflow. Leading to countDofs where the for loop iterates a wrong number of time :
So countDofs returns the wrong value in
And finally, mWorldMotionMatrix is allocated with the wrong value :
Which lead to the read segfault in
I didn't found this 255 links limit anywhere in the documentation or in the source code comments, it's weirdly hardcoded without any checking (even with the checked configuration), so it looks like a bug. I'm keeping the discussion open in case someone have a way to create an articulation with more than 255 links, since this limit only seems to exist for the constraint solver that I don't need. I'll try to use standard joints in the meantime which sadly don't support reduced coordinates. |
Beta Was this translation helpful? Give feedback.
-
Thank you for the detailed issue description and finding the culprit! I created a ticket for us to look at this, but cannot offer a timeline for fixing this, I'm glad you have a workaround for now. |
Beta Was this translation helpful? Give feedback.
Uh oh!
There was an error while loading. Please reload this page.
Uh oh!
There was an error while loading. Please reload this page.
-
Hello,
I was wondering if someone already had a similar issue while initializing big articulations.
I have a recursive function that creates random articulation tree, and when the articulation gets too big (>=256 links) the physx function
physx::Dy::FeatherstoneArticulation::setupInternalConstraintsRecursive
inphysx/source/lowleveldynamics/src/DyFeatherstoneArticulation.cpp
segfault. (But it's working fine with 255 links).I read the documentation and the articulation doesn't seem to have a link number limit (except a 64 one in older version), so it's a bit weird.
It's the 2551st line, which is the culprit :
Using GDB,
jointDatum.jointOffset
= 4294967295 = 0xFFFFFFFF and the function arguments looks really weird sincelinkCount
= 9 andlinkID
= 26.In my project, I think I don't even need the constraint solver since I'm only doing collision detection while moving manually the joints and I'm ignoring all resulting forces (gravity is set to 0 and the contact forces are disabled with a collision filter).
So if there is a way to disable this function call, it works for me as well.
I'm using the checked configuration with the 5.6.0.bcc9863a version.
Thanks.
Beta Was this translation helpful? Give feedback.
All reactions