Physics and simulation parameters for grasping and picking tasks - objects slipping away

Hi everyone,

I am having trouble finding a set of parameters for smooth simulation and physics. The goal is to find a set of parameters that allows both to detect collisions without issues like objects intersecting/penetrating each other and fine-grained tasks such as grasping/picking objects without the objects slipping away from the hand.

Here are the 2 main problem I am facing:

  • When the robot walks towards the table and collides, the collision/contact is detected and simulated for a couple of steps (table bounces/flies away), after that the robot walks through the table.
  • When trying to grasp an object, the object shifts or slips away.

This are some of the resources I used so far to fix the issue, they have helped to improve the simulation and the physics but it’s still not good:

Parameters I have been playing around with:

  • stabilization_threshold, max_depenetration_velocity, density, bounce_threshold_velocity, friction_offset_threshold, friction_correlation_distance, contact_offset, rest_offset

Does anyone know a good setting for these parameters or which further parameters i could tune to improve the simulation and physics? Most importantly, I need a setting that allows for grasping and picking objects.

Here is the set of parameters that i am currently using:

sim:
  dt: 0.0083 # 1/120 s
  use_gpu_pipeline: ${eq:${...pipeline},"gpu"}
  gravity: [0.0, 0.0, -9.81]
  add_ground_plane: True
  add_distant_light: True
  use_flatcache: False
  enable_scene_query_support: False
  disable_contact_processing: False

  # set to True if you use camera sensors in the environment
  enable_cameras: True

  default_physics_material:
    static_friction: 1.0
    dynamic_friction: 1.0
    restitution: 0.0

  physx:
    worker_thread_count: ${....num_threads}
    solver_type: ${....solver_type}
    use_gpu: ${eq:${....sim_device},"gpu"}
    solver_position_iteration_count: 4
    solver_velocity_iteration_count: 0
    contact_offset: 0.02
    rest_offset: 0.0
    bounce_threshold_velocity: 2.0
    friction_offset_threshold: 0.01
    friction_correlation_distance: 0.0005
    enable_sleeping: True
    enable_stabilization: True
    max_depenetration_velocity: 100.0

    # GPU buffers
    gpu_max_rigid_contact_count: 524288
    default_buffer_size_multiplier: 25.0
    gpu_max_rigid_patch_count: 81920
    gpu_found_lost_pairs_capacity: 10240
    gpu_found_lost_aggregate_pairs_capacity: 10240
    gpu_total_aggregate_pairs_capacity: 10240
    gpu_max_soft_body_contacts: 1048576
    gpu_max_particle_contacts: 1048576
    gpu_heap_capacity: 67108864
    gpu_temp_buffer_capacity: 16777216
    gpu_max_num_partitions: 8
    gpu_collision_stack_size: 67108864
    density: -1

# sim asset configs here
  TiagoDualHolo:
    # -1 to use default values
    override_usd_defaults: False
    fixed_base: False # Needs to be false here but can be set in usd file. Even with fixed_base, virtual joints can still be used to move the base.
    enable_self_collisions: False
    enable_gyroscopic_forces: True
    # also in stage params
    # per-actor
    solver_position_iteration_count: 4
    solver_velocity_iteration_count: 0
    sleep_threshold: 0.005
    stabilization_threshold: 0.001
    # per-body
    density: -1
    # max_depenetration_velocity: 100.0
    # per-shape
    #contact_offset: -
    #rest_offset: 0.001

  object:
    # -1 to use default values
    override_usd_defaults: False
    enable_self_collisions: False
    enable_gyroscopic_forces: True
    # also in stage params
    # per-actor
    solver_position_iteration_count: 4
    solver_velocity_iteration_count: 1
    sleep_threshold: 0.005
    stabilization_threshold: 0.001
    # per-body
    density: 50.0
    max_depenetration_velocity: 3.0
    #contact_offset: -inf
    #rest_offset: 0.001

Best regards,
Sabin

Hi,

I had faced a similar issue in the past where the grasped object would fall. In my case, I resolved it by increasing solver_position_iteration_count and solver_velocity_iteration_count to around 16 or 32 and setting static_friction and dynamic_friction within the object’s PhysicsMaterial to 1.0.
I understand that your environment and settings may vary, but here are the settings I used.

env:
  numEnvs: ${resolve_default:4096,${...num_envs}}
  envSpacing: 5.0
  resetDist: 1.0
  controlFrequencyInv: 2 # 60 Hz
  gamma: 0.999
  horizon: 600

sim:
  dt: 0.0083 # 1/120 s
  use_gpu_pipeline: ${eq:${...pipeline},"gpu"}
  gravity: [0.0, 0.0, -9.81]
  disable_gravity: False
  add_ground_plane: True
  add_distant_light: True
  use_flatcache: True
  enable_scene_query_support: True
  disable_contact_processing: False
  enable_cameras: False # set to True if you use camera sensors in the environment

  default_physics_material:
    static_friction: 1.0
    dynamic_friction: 1.0
    restitution: 0.0

  physx:
    worker_thread_count: ${....num_threads}
    solver_type: ${....solver_type}
    use_gpu: ${eq:${....sim_device},"gpu"} # set to False to run on CPU
    solver_position_iteration_count: 16
    solver_velocity_iteration_count: 16
    contact_offset: 0.005
    rest_offset: 0.0
    bounce_threshold_velocity: 0.2
    friction_offset_threshold: 0.01
    friction_correlation_distance: 0.025
    enable_sleeping: True
    enable_stabilization: True
    max_depenetration_velocity: 5.0

    # GPU buffers
    gpu_max_rigid_contact_count: 524288
    gpu_max_rigid_patch_count: 33554432
    gpu_found_lost_pairs_capacity: 17060160 # 524288
    gpu_found_lost_aggregate_pairs_capacity: 17060160 # 262144
    gpu_total_aggregate_pairs_capacity: 1048576
    gpu_max_soft_body_contacts: 1048576
    gpu_max_particle_contacts: 1048576
    gpu_heap_capacity: 33554432
    gpu_temp_buffer_capacity: 16777216
    gpu_max_num_partitions: 8

  # sim asset configs here
  robot:
    # -1 to use default values
    override_usd_defaults: False
    enable_self_collisions: False
    enable_gyroscopic_forces: True
    # also in stage params
    # per-actor
    solver_position_iteration_count: 16
    solver_velocity_iteration_count: 16
    sleep_threshold: 0.005
    stabilization_threshold: 0.005
    # per-body
    density: -1
    max_depenetration_velocity: 5.0
    # per-shape
    contact_offset: 0.005
    rest_offset: 0.7e-5

  block:
    # -1 to use default values
    override_usd_defaults: False
    make_kinematic: False
    enable_self_collisions: False
    enable_gyroscopic_forces: True
    # also in stage params
    # per-actor
    solver_position_iteration_count: 16
    solver_velocity_iteration_count: 16
    sleep_threshold: 0.005
    stabilization_threshold: 0.005
    # per-body
    density: -1
    max_depenetration_velocity: 3.0
    # per-shape
    contact_offset: 0.005
    rest_offset: 0.7e-5

  table:
    # -1 to use default values
    override_usd_defaults: False
    make_kinematic: True
    enable_self_collisions: False
    enable_gyroscopic_forces: True
    # also in stage params
    # per-actor 
    solver_position_iteration_count: 16
    solver_velocity_iteration_count: 16
    sleep_threshold: 0.005
    stabilization_threshold: 0.005
    # per-body
    density: 1000
    max_depenetration_velocity: 3.0
    # per-shape
    contact_offset: 0.005
    rest_offset: 0.7e-5

  parts:
    size: 0.04
    mass: 0.01
    density: 100
    static_friction: 1.0
    dynamic_friction: 1.0
    restitution: 0.0

I hope this information is helpful to you.

1 Like

Thanks @makoto.sato385!
Our issue right now is that, even with these settings above, the object doesn’t get picked up. It seems like it is a friction issue (See attached short video)

Our objects also seem to have static and dynamic friction in the Physics material set to 1.0 . So we think that the robot itself is the culprit. Do you mind sharing how you generated the USD of your Robot? And did you change any friction settings there?

Thanks a ton @makoto.sato385 !
We were able to get a reliable grasping simulation working.
I think the information in this thread should be added as a tutorial in the Isaac Sim documentation.

The key enablers for the grasping simulation are:

  • Using appropriate friction parameters:
def create_prop_material(self):
    self._stage = get_current_stage()
    self.propPhysicsMaterialPath = "/World/Physics_Materials/PropMaterial"

    utils.addRigidBodyMaterial(
        self._stage,
        self.propPhysicsMaterialPath,
        density=5000, # It depends on the mass and size of the object.
        staticFriction=1.0,
        dynamicFriction=1.0,
    )
def add_prop(self):
    prop = DynamicCuboid(prim_path=self.default_zero_env_path + "/prop",
                            name="prop",
                            translation=self._prop_position,
                            orientation=self._prop_rotation,
                            size=self._prop_size,
                            density=self._prop_density,
                            color=torch.tensor([0.2, 0.4, 0.6]))
    self._sim_config.apply_articulation_settings("prop", get_prim_at_path(prop.prim_path), self._sim_config.parse_actor_config("prop"))

    physicsUtils.add_physics_material_to_prim(
        self._stage,
        self._stage.GetPrimAtPath(self.default_zero_env_path + "/prop"),
        self.propPhysicsMaterialPath
    )
  • **Use appropriate control strategy for the robot joints **
    Using effort control for the gripper does work well. What can also work fine is using PD control using “set_joint_position_TARGETS()”.
    One of our main mistakes was that we were using “set_joint_positions()” directly and using this function to set the joints does not simulate physics at all. So our gripper was able to grasp the object but not pick it up since the arm IK was using set_joint_positions and not set_joint_position_targets.

Hope this helps someone else

4 Likes

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