Is it possible to enable self-collision without considering parent links or specific links of a same asset/actor?.
The create actor appears to have a parameters for doing this but its is unclear and undocumented how to use this:
create_actor(self: Gym, env: Env, asset: Asset, pose: Transform, name: str = None, group: int = - 1, filter: int = - 1, segmentationId: int = 0) → int
Creates an Actor from an Asset
Parameters
param1 (Env) – Environment Handle.
param2 (Asset) – Asset Handle
param3 (isaacgym.gymapi.Transform) – transform transform of where the actor will be initially placed
param4 (str) – name of the actor
param5 (int) – collision group that actor will be part of. The actor will not collide with anything outside of the same collisionGroup
param6 (int) – bitwise filter for elements in the same collisionGroup to mask off collision
param7 (int) – segmentation ID used in segmentation camera sensors
The bitwise filter for elements in the same collisionGroup to mask off collision seems to possible enable this behavior. What is the structure of this bitwise filter? What order of rigid_bodies does it follow. Can you provide an example?
These parameters are meant to be applied on a per-actor basis, it likely won’t be helpful in your case for trying to mask off collision between bodies of the same actor. If your asset is in MJCF format, you could check out the Creating Actors section in the docs under programming/assets. It will allow you to specify in your asset file which bodies could collide with each other. We utilize this function in our Shadow Hand example.
It may be possible with the MJCF asset through defining specific <pair> sets under the <contact> tag. You can take a look at the Shadow Hand asset as an example - under assets/mjcf/open_ai_assets/hand/shared.xml
in order to enable self-collision,collision_filter in gym.create_actor() need to be set as -1 (predefined collision) or 0(enable collisions between all shapes in the actor)
If bodies in your mjcf asset still became capsules and boxes, try add <compiler meshdir="MESHDIR" texturedir="TEXTUREDIR"/>
on your mjcf file.
Maybe your shape sources are not properly recognized while loading.
is it possible to enable/disable specific collisions with a URDF defined model? I want to deactivate self collision with each link’s parent, but allow collision with every other link in the kinematic chain for a single actor/asset. is that possible? thank you!
I find that modify the shape properties might be a solution for URDF format (func set_asset_rigid_shape_properties). By properly design the shape filter value, I think probably we can handle any collision combinations.
Thank you very much for the precious info!
Yes, that’s true. But I think it’s nearly impossible to set filter field for all the rigid shapes in practice because we can’t distinguish which rigid shape is the target shape. And the number of rigid shapes is different from the rigid body so we can’t infer the target rigid shape by the index of rigid bodies.
Or maybe we can do it, but I missed some documents about it. Would you please tell me your methods about distinguish the ‘target’ shapes?
complement:
I found the solution! we can use get_asset_rigid_body_shape_indices() to get the mapping relationship between rigid shapes and rigid bodies.
Yea. While in my task, I just referred to the skeleton tree of urdf. BTW, Isaac gym loads the asset that each components are listed in DFS order. I found that difficult to take an automatic way to design the binary filter mask, so I simplified my problem and manually did it.
PS. Setting param6 to ‘-1’ in create_actor to use the asset collision setting should work but it seems that it ignores all collision.
Yes, When pass self_collision value(such as -1 or 0 or 1) to the create_actor(), it will set the same value to all the shapes, so it’s better to manually design the value for specific filter filed.