Closed kentar0kozai closed 4 weeks ago
Hello,
Thanks for using our repository! Yes, this is a problem we are familiar with; we found that the object penetration depended on:
The error comes from the interactions calculated through the physics engine. To fix the issue, we increased the physics frequency of the PhysiX engine to 240 Hz for the grippers that had this problem. You can do this for different grippers by changing the "physics_frequency" in the "gripper_isaac_info.json" file. https://github.com/IRVLUTD/isaac_sim_grasping/blob/f23d790eb5e3853cb657215b05d5ed5a51ad73a5/grippers/gripper_isaac_info.json#L81C1-L83C30
Thanks for the reply!
I understand. I will try increasing the physics frequency.
I also observed that the object was already falling at the start of grasping.
I can't say for sure since I have only adjusted the Allegro hand, but I found that setting the Maximum Joint Velocity in the usd file to 5-6 times (about 500) resulted in a more natural grasping.
Please give it a try!
I have added code to views.py to determine if the hand is stuck in the object. Although the number of samples for the initial grasp pose is reduced, I think we can now properly evaluate Grasp Quality. Does this match your ideal? (I understand that it is best to adjust the output of GraspIt!.)
def physics_step(self, step_size):
"""Function runs before every physics frame
step_size: time since last physics step. Depends on physics_dt
"""
# Check for active workstations
# print("Outside step", time.time()-self.t)
# self.t= time.time()
active_ind = np.argwhere(self.current_job_IDs >= 0) # ws indices
if len(active_ind) > 0:
# Calculate falls
current_positions, current_rotations = self.objects.get_world_poses(active_ind)
t_error = abs(te_batch(self.init_positions[active_ind], current_positions))
# Object that fell
finish_ind = active_ind[t_error > 0.6]
if len(finish_ind) > 0:
self.test_finish(finish_ind)
# Check for penetration (hand model penetrating the object)
for ind in active_ind:
contact_forces = self.objects.get_net_contact_forces(indices=[ind])
if contact_forces is not None and np.any(contact_forces < -1.0):
self.test_finish([ind])
break
.
.
.
https://github.com/user-attachments/assets/429861d4-b5b4-4fa7-9226-ff85e7e26a8f
Thanks for the reply! I understand. I will try increasing the physics frequency. I also observed that the object was already falling at the start of grasping. I can't say for sure since I have only adjusted the Allegro hand, but I found that setting the Maximum Joint Velocity in the usd file to 5-6 times (about 500) resulted in a more natural grasping. Please give it a try!
Hello,
Thanks for sharing! In some grasps, one finger link can come into contact with the objects much faster than the other links, which will trigger the initialization of the grasps. If you want to have multiple contacts secured before the grasps are considered as ready, you can increase the value of "contact_th" in the "gripper_isaac_info.json". The grasps we filtered were GraspIt! grasps that were in the most part very close to contacting the objects therefore for most grasps even a contact_th of one the object doesn't fall after initialization; in the case of it being a good grasp.
I have added code to views.py to determine if the hand is stuck in the object. Although the number of samples for the initial grasp pose is reduced, I think we can now properly evaluate Grasp Quality. Does this match your ideal?
This is a nice way of determining the object penetration, nonetheless be mindful of the differences in forces and frequencies of multiple grippers. the views.py is the general behavior of every gripper, so a contact threshold of -1.0 may work really well with the Allegro gripper at 240 Hz physics but filter a lot of grasps from other grippers at lower frequencies. This was the case for us when developing the simulation behaviors. Our standalones could certainly be improved with a reliable method of detecting object penetration; we may even implement something very similar in the future. Thank you for the recommendation!
Sorry for the late reply, I was on vacation.
If you want to have multiple contacts secured before the grasps are considered as ready, you can increase the value of "contact_th" in the "gripper_isaac_info.json".
Thanks, I'll give it a try!
Please close this issue as it is almost resolved. Thank you for your kind attention. Please keep up the good work!
First of all, I would like to express my great respect for your research. It's very impressive.
Now that I have run the demo, I have found one problem.
When simulating grasps generated by GraspIt! using standalone.py, the hand often penetrates the object.
Is there a way to prevent this? Any insight on this would be greatly appreciated, thanks.