About isaac sim 2023.1.1 crash bug on robotic arm,Invalid for collision grabbing

I am simulating a robotic arm simulation in Isaac sim, and my robotic arm gripper is RevoluteJoint. At the same time, I have seen some similar problems on the forum, but there is no solution.
66666

I defined the gripper and used RMPflow motion trajectory.

pick_positions = my_controller.arm_controller.forward(
                target_end_effector_position=np.array([0.0, 0.26, 0.1]),
                target_end_effector_orientation=np.array([1, 0, 0, 0]))

articulation_controller.apply_action(pick_positions)

But when I closed the fixture, it had a strange problem. The fixture passed through objects with collisions and did not clamp onto the Cube. Meanwhile, I saw some similar questions on the forum. The code for closing the gripper is:

gripper_positions = my_denso.gripper.get_joint_positions()
            my_denso.gripper.apply_action(ArticulationAction(joint_positions=[gripper_positions[0] - 0.01, gripper_positions[1] - 0.01]))

and

my_denso.gripper.close()

But the result was not good, the fixture closed normally, but it passed through the Cube I tried the scraper collision types SDF and Convex Hull, and both achieved the same results without any effect.

Because I have seen many people have the same experience on the forum, I want to know if this is a bug or if there are any alternative solutions to solve this problem. It is a terrible problem.

It’s really a bug, I’ve tried many times, including exporting URDF with an Isaac sim, but it still doesn’t work. I think the development team should be aware of this, but I haven’t heard back from any NVIDIA developers.

He is currently in a completely unusable state.

Assuming your colliders are well defined, most likely your issue is that joint gains and/or max force for the gripper joints is set too high, and the joint position is dominating the simulation solver.

The simulation works as an error minimization problem, and the joint stiffness acts as an error weight attribute - If it’s set too high, this error will dominate the depenetration error set by the collider, and the end result is that it will favor setting the right joint pose instead of not penetrating the solid object.

You can have as an analogy for real life that you have motors that are just too strong (and no force feedback cutoff), and it squishes the cube in to achieve the goal position. Except this cube is non-deformable so it doesn’t get squished in simulation.

Try tuning the joint(s) drive max force to ensure it won’t dominate the simulation. Too low values will result in failed grasp, and too high values will cause this disproportionate penetration.

@rgasoto

Thank you very much for your assistance; I have successfully resolved the penetration issue. By adjusting the Max Force to 0.1 (a very low value), I was able to successfully grab the Cube, which has a mass of 0.1.

However, with this adjustment, I encountered a new problem. When I increased the mass of the Cube to 1.0 (with a friction of 1.0), it dropped after being grabbed. If I increase the Max Force to make the grip stronger, it leads to other issues such as penetration or the Cube starts to shake unstably until it falls. My “Damping” and “Stiffness” values are set to “100000” and “1000000” respectively. I would like to know how to adjust these settings to grab a Cube with greater mass. Simply adjusting the “Max Force” seems incorrect.

Max Froce 0.5, Cube mass 1.0
1

Max Froce 0.1, Cube mass 1.0
2

Besides changing the Max Force, is there any otherBesides changing the Max Force, is there any other strength, as I see many as I see many people in the forum having similar issues?

Looking forward to your assistance.
Best regards.

There are a lot of settings and parameters that can be adjusted. In this case I’m seeing jittering at the contact and for that I would take a look at the meshes. This happens, for example, if you have one item meshed with an SDF collider and a second meshed with a triangle collider. I’ve had the best success if all of my colliders are SDF meshes.

If any of your meshes have their meshes auto-computed that can cause trouble too; I would go through each collider and make sure they have a reasonable mass set.

Another issue could be if your cube is very small, say 1mm cubed but has a mass of 1kg. I’ve also had trouble when I accidentally had a cube that was 1km cubed and had a mass of 1kg, it’s important to check all of those units and measures.

For help with an ongoing project, I would recommend you join the discord community. You can hang out with like-minded people there and get fast responses and suggestions for project building and tuning like this.

Besides @StrainFlow suggestions - also tuning the joint damping and stiffness will help stabilizing the contact - since the original issue of the joint position dominate the error still persists - it’s just modulated by the max force.

I’d start with zero or no damping, and gradually increase the joint stiffness until it behaves within specification and reaches a stable grasp. Additionally, If you are in Isaac sim 4.0 you can also try modeling the gripper using a mimic joint.

These tutorials have a lot of things that could help you with this tuning:
https://docs.omniverse.nvidia.com/isaacsim/latest/advanced_tutorials/tutorial_advanced_joint_tuning.html
https://docs.omniverse.nvidia.com/isaacsim/latest/advanced_tutorials/tutorial_advanced_rigging_complex_structures.html

Another thing to check is how your collision meshes are - since your grippers are teethed, convex decomposition may require some fine-tuning. one thing you can do is using an external mesh as collider (for example a cube that matches the gripper tip) to simplify the collision shape. As long as that body is a subcomponent of the Rigid Body Prim, it can have a collisionAPI attached to it and behave as a collider, even if it’s invisible on the scene. Just be sure to remove the collisonAPI from the visual mesh.

This topic was automatically closed 14 days after the last reply. New replies are no longer allowed.