Closed articulation simulation problem

Hello everybody,

I have created a new model of the ANYmal C robot with the adaptive feet described in this paper.
The instanceable asset can be downloaded here
anymal_c_softfoot_q.zip (4.2 MB)
In the folder there is the instanceable asset anymal_c_softfoot_q.usd and the anymal_c_softfoot_q_meshes.usd file containing all the meshes referenced by the instanceable asset.
These adaptive feet have a closed kinematics structure. Each foot is made up of 3 chains (right, middle and left), each made up of 9 links (5 inner and 4 outer). Each chain has 10 joints (counting also the ones that attach the entire chain to the front and back roll links).
Now, the simulation perfectly works if I leave the open kinematics structure, without attaching the last link of each chain to the corresponding back roll link. But I cannot use the feet in these way, because they would not have the adaptive feature they were designed for. So I need to close the kinematic chain.
Let’s take, for example, the left chain of the Left Front foot.
I add the 10th joint of the chain by adding a joint between the back roll link and the 9th link of the left chain, as shown in this picture

I exclude the joint from the articulation to make it work, I set the maximum joint velocity and upper/lower limits like all the other joints of the same type, keeping the joint friction equal to 0 as the joint is excluded from the articulation.

I press play and this is what happens


the robot basically disappear, it looks like it was wiped out.

While disabling this last added joint everything works (except the correct behaviour of the adaptive feet of course)

What should I do to make everything work correctly, closing the kinematics of all the chains of all the feet as needed?

Thanks a lot in advance for all your kind and precious replies.
If you could directly correct the usd file I shared and then share back the updated version I would be extremely happy and thankful. It would be greatly appreciated.

@antonello.scaldaferri.as - can you please also post the version with the missing joints that are causing the issue? I can’t see them in the asset you uploaded.

It’s easy to disable via the enable checkbox:
image

We’ll look into the issue.

anymal_c_softfoot_q.zip (4.2 MB)
Sorry for the late response.

Here is the complete version of the robot with all the missing joints that are causing the issue, that are the following:
softfoot_LF_foot_left_chain_10_joint
softfoot_LF_foot_middle_chain_10_joint
softfoot_LF_foot_right_chain_10_joint
softfoot_LH_foot_left_chain_10_joint
softfoot_LH_foot_middle_chain_10_joint
softfoot_LH_foot_right_chain_10_joint
softfoot_RF_foot_left_chain_10_joint
softfoot_RF_foot_middle_chain_10_joint
softfoot_RF_foot_right_chain_10_joint
softfoot_RH_foot_left_chain_10_joint
softfoot_RH_foot_middle_chain_10_joint
softfoot_RH_foot_right_chain_10_joint
they are in the chain_9_link body of the respective chain.

They are all excluded from the articulation, to solve the kinematic loop closures.
If you disable all of them the simulation works, but the chains open and I don’t want that to happen.

Please help me.
Thanks a lot in advance.

I tried out your USD file in omniphysics.

I tried running all combinations of CPU/GPU and TGS/PGS solver.

I found that TGS and PGS on GPU were both unstable.

I then found that TGS and PGS on CPU were both stable.

This feels like a bug in physx. It’s hard to tell right now. If there was anything in the configuration that cannot be meaningfully handled by the solver, I’d expect GPU and CPU to behave pretty much the same. It’s hard to say if this is just different float precision (we use simd on cpu but regular float operations on gpu) or something more fundamental in physx. We’ll need to take a look.

One thing I did notice is that largestMass/smallestMass is about 300. We should be able to handle that because those masses are only indirectly coupled. However, stability is always improved with smaller ratios. One thing to try would be to set the masses directly rather than using the automatically generated masses.

In the meantime, can you revert to cpu dynamics?

Cheers,

Gordon

Hi,
we now have the same problem.

Have you found the fix?

Have you tried running the dynamics on CPU? This seemed stable when I last tried this asset.

Yes, we tried that as well, but this introduced a weird error in the initialization of the quadrupeds in the simulation environment.

We are trying to train an RL algorithm for our quadruped, so we use the Anymal task from omniisaacgymenvs as our template. We really hope this will run on the GPUs so that we can take advantage of the fast training times.

@finn.gross.maurer - Gordon is working on fixing the GPU issues / discrepancies for the loop closure, but the fixes will not be available until the release after next.

For the initialization errors, it is best if you could provide a detailed description and create a separate forum post for the omniisaacgymenvs team to have a look.

Hi @philipp.reist.
Thanks for the answer. When do you think the release will be available?

I will do some further research on the initialization errors and the closed kinematic chain issue. When I get some time, I can post a full description of the task and the problems we encounter.

I don’t have a date for the release after next, but @rthaker might be able to provide an estimate.

Is there are way you could work around the GPU loop closure issue with a simplified model of the compliant Anymal feet? E.g. a series of prismatic joints connecting smaller contact blocks to the feet so that they can adapt to the surface?

Thank you for taking the time to report the initialization issues!

Philipp

The posts here are a bit misleading. We are trying to simulate our own robot with some special “loop-closure” legs. See: Simulating quadruped with "five bar linkage" legs

I just think this may be the same problem as mentioned in the post here. The simulation works fine when the bottom “paw” joint is not connected, but once connected the simulation becomes unstable.

Here is the illustration from the linked post:
image

Thank you for the clarification Finn,

Would you be able to share a minimal repro in USD with us to have a look?

With that repro, you can also check whether CPU/GPU PGS/TGS solvers have an impact on the simulation result.

Thank you,
Philipp

Yes I will try to have it done by Monday.

A quick observation from yesterdays debugging:
It looks like increasing the articulations position and velocity count makes the problem worse, which I think is odd? I will check it out more this weekend and then comment it on my next post.

Have a good weekend :D

Thank you Finn. Yes, iterations should definitely make it better. Could you compare CPU and GPU by any chance already?

Have a great weekend and looking forward to your repro.
Philipp

Hi,
We have now tried to simplify the model.
The quadruped is defined in “quadruped_simplified_meshes.usd” and is placed in a world with a ground plane in “quadruped_in_world.usd”.

We didn’t get it to work with either CPU or GPU.

quadruped_in_world.usd (8.0 KB)
quadruped_simplified_meshes.usd (70.6 KB)

We also cloned the “anymal learning to walk” task in omniisaacgymenvs, and ran it with our quadruped. Here the “dissapearing robot” bug still occurs, though less frequently. We hypothesize that this may be due to the joint drives preventing undefined/illegal joint configurations:

Hi, our group designed a series of close-chain robots and I have successfully trained the robot in Isaac Sim. But it did take me a long time to solve the problems of close-chain simulation. In the beginning, I encountered nearly the same problem as yours that the robots just flew away whenever they reset. Here are some steps that I have tried:

  1. When you call the function ArticulationView.set_joint_positions(positions, indices, joint_indices), you have to set the position of all the joints (including those that have already been excluded from articulation, i.e., passive joints that are not driven by motors)

  2. Set the ArticulationRoot to the robot base but not the top-level prim. I do not figure out why this is important but it seems that the default ArticulationRoot will cause some problems. The prims of Anymal should be something like:

  • Anymal
    • AnymalBase

By default, the ArticulationRoot is set to Anymal, changing it to AnymalBase may avoid some issues.

  1. Increase the position iterations. If this value is small, you may observe the joints having undesired displacements. But this value may only take effect if the “disappearing” problem is solved.

Our quadruped robot has legs with a four-bar linkage mechanism which is the same as your simplified quadruped, hope it helps!

Hi Alan, thank you for your response!

We have tried all three suggestions already, but with no success. Do you have any USD files we can take a look at?

Hi @gyeoman,

I tried all the possible combinations between broadphase type (GPU, MBP, SAP), solver type (PGS, TGS) and collision system (PCM, SAT), in total 3x2x2 trials, but none of these worked on my workstation, which uses NVIDIA GeForce RTX 3060 Laptop GPU.
I have also tried them in an Isaac Sim container running on a remote workstation, that I have access on, which uses a Tesla T4 GPU.

As @philipp.reist suggested, I am using a simplified model of the adaptive feet. I have actually implemented a lot of them, some keeping the closed kinematics structure and others open. Only the open ones work. I have not been able to implemented a working simplified model with the closed kinematics structure.

The simplified model of the five bar linkage quadruped by @finn.gross.maurer seems to work quite good now, but it has way less joints that the ANYmal with adaptive feet robot model.
@finn.gross.maurer if you still experience few dissapearing bugs, try to limit the joint torques that you apply by the set_joint_efforts method. If instead you are using the DriveAPI on the robot joints, try to lower the stiffness and damping parameters. I had the same problem with Solo 12 and I solved like this. Also changing the MassAPI parameters (mass, center of mass, diagonal inertia and principal axes) of the links could help.

To answer @AlanSunHR, I need to control the robot dynamically, that means taking into account the full dynamics of the system and its surrounding environment, non kinematically. The set_joint_positions method, that you mentioned, changes the robot joint positions without taking into account the joints dynamics, but instead it sets the joint position explicitly, obtaining in this way a kinematic control.
The dynamic control is obtained either by means of the set_joint_efforts method, or the set_joint_position_targets method in the case the DriveAPI is applied to the robot joints.
I am aware also of the fact that you have to set the position of all the joints, including both passive that active ones. Anyway, if this would be the problem, it would be easy to debug, since, if you set the wrong number of joint positions/efforts, a tensor shape mismatch error occurs, telling you both how many joint positions/efforts you set and how many instead need to be set, solving the issue immediatly.
I have also tried to apply the ArticulationRootAPI not to the top-level prim, but neither this worked.
I have also tried to increase the position/velocity iterations of the solver, but as you said it is useless if you first don’t solve the disappearing problem.

I don’t know what else to do. I hope that, whatever the bug is, it will be solved sooner or later.

Thanks to all of you for your interesting answers. Sad that none of those solved my problem.

Hope either @gyeoman, or @philipp.reist will come with a solution one day.

Still thanks a lot for your contributions.

Antonello

Thanks for the writeup @antonello.scaldaferri.as - yes we are working on fixing the GPU loop closure issues and hope to publish those asap.

@finn.gross.maurer - looking at the model I was wondering: Did you try breaking the loop at the paw joints (exclude from articulation there instead of on the front knees)?

Otherwise I think it’s the same GPU loop closure problem. CPU sim looks solid (if I add angular drives to all revolutes, looks like you tuned them already?):

Given that our CPU sim is fine I am hopeful we’ll find the issue soon. Thank you all for your patience and the reports!

For the record, the same exact setup with GPU sim goes NaN too

@philipp.reist Yes we tried breaking the loop at the paw at first, but then we thought it might be “easier” for the solver if the joint closer to the collision is part of the articulation. But this was just a guess…

We also wonder how we best should implement the non-actuated joints (front- and backknee + paw). Just a normal revolute joint + some friction for stability?