erwincoumans / tiny-differentiable-simulator

Tiny Differentiable Simulator is a header-only C++ and CUDA physics library for reinforcement learning and robotics with zero dependencies.
Apache License 2.0
1.2k stars 129 forks source link

Spherical Joints at Contact, Mass Matrix #123

Closed jyf588 closed 2 years ago

jyf588 commented 3 years ago

Hi all,

I created a simple humanoid model with 1 spherical joint and all other joints fixed. When I throw this humanoid to the floor, I got array out of bound assertion failures and simulation stopped without error messages.

After some digging, it appears that when constructing the mass matrix for contact resolution, the spherical joint case might indeed have some issues. I ended up changing this line to Algebra::assign_block(*M, Algebra::transpose(Fi), 0, qd_i, 6, 3);, as the way assign_block is implemented for 6*3 matrices seemed to cause out-of-bound errors due to the "fake transpose".

With this mod, the sim successfully runs, but the energy does not seem to decrease over time with zero restitution. Please see the video attached. In fact, if we wait long enough, the sim eventually explodes and gives NaNs.

I checked related issues #76 , #91 and made sure my model does not have inertial offset at root. The urdf model and python code is also attached.

Attachments

Thanks for helping with this issue! Yifeng

erwincoumans commented 3 years ago

Thanks for the report, haven't had the time to check this out yet. From the video, one leg seems to be freely moving (unmotorized) and all the other joints are fixed?

erwincoumans commented 2 years ago

Thanks for the report. I had a look at your URDF and could reproduce the issue. With some fixes, the URDF can be loaded in C++ code, modifying the tiny_urdf_parser_opengl_example.cpp (see attached zip). Haven't tried your Python script yet. Fixes are in here: https://github.com/google-research/tiny-differentiable-simulator/pull/16 tiny_urdf_parser_opengl_example.zip Here is a video, note that a small amount of joint damping is applied, otherwise the simulation becomes unstable (gains energy): https://www.youtube.com/watch?v=mRfVjEAv538 PyBullet behaves similar, when the default link and joint damping is disabled. See attached PyBullet script. So it is important to control the spherical joint, for example using a PD controller.

pybullet_check.zip

erwincoumans commented 2 years ago

This should work better now. If not, please re-open a new issue.