isaac-sim / OmniIsaacGymEnvs

Reinforcement Learning Environments for Omniverse Isaac Gym
Other
764 stars 202 forks source link

get_net_contact_forces is not working under Isaac Sim 2023.1.0 #88

Open robinvetsch opened 8 months ago

robinvetsch commented 8 months ago

Hi all,

To detect self-collisions of a robot arm, I implemented a method under Isaac Sim 2022.2.0 to extract and evaluate the contact forces of single robot prims. like the following function:

def check_collisions(self):
        """
        Method: check_collisions()

        This function checks if a collision occurs
        """
        collision_shoulder = self._robots._ur_shoulder_collision.get_net_contact_forces(clone=False)
        collision_upper_arm = self._robots._ur_upper_arm_collision.get_net_contact_forces(clone=False)
        collision_forearm = self._robots._ur_forearm_collision.get_net_contact_forces(clone=False)
        collision_wrist_1 = self._robots._ur_wrist_1_collision.get_net_contact_forces(clone=False)
        collision_wrist_2 = self._robots._ur_wrist_2_collision.get_net_contact_forces(clone=False)
        collision_end_effector = self._robots._ur_endEffectors_collision.get_net_contact_forces(clone=False)

        #set the collision value to true, if a collision occurs
        self.collision_detected = torch.tensor((collision_shoulder.any(-1, keepdim=True) | 
                                                collision_upper_arm.any(-1, keepdim=True) |
                                                collision_forearm.any(-1, keepdim=True) |
                                                collision_wrist_1.any(-1, keepdim=True) |
                                                # collision_end_effector.any(-1, keepdim=True) |
                                                collision_wrist_2.any(-1, keepdim=True)), device=self._device)

        #reshape the tensor
        self.collision_detected = torch.reshape(self.collision_detected, shape=(self.collision_detected.shape[0],))

For this I set the flag "track_contact_forces" in the Robot_view class in RigidPrimView to true. With Isaac Sim 2022.2.0 the task worked without problems. After updating to version 2023.1.0, I get the following error:

image

As backend, torch is used, I tested this with a simple print in the file: "/home/robin/.local/share/ov/pkg/isaac_sim-2023.1.0/extsPhysics/omni.physics.tensors-105.1.9-5.1/omni/physics/tensors/impl/api.py"

The example with FrankaFactory works where the get_net_contact_forces is also used, but I have no idea what is different.

Do I have to make further changes so that the determination of the contact forces works again.

Many thanks for the help.

Milad-Rakhsha commented 8 months ago

Can you check out and see if there are other warning/error messages before this one shows up? There haven't been changes directly related to this API with the new update. It is likely something else on the physics side is causing this. It would be great if you could provide a small repro so we could further look into any possible issues

robinvetsch commented 8 months ago

Can you check out and see if there are other warning/error messages before this one shows up? There haven't been changes directly related to this API with the new update. It is likely something else on the physics side is causing this. It would be great if you could provide a small repro so we could further look into any possible issues

I ran the simulation with a slightly different simulation setup. Unfortunately, I can not post any pictures due to confidentiality. The robot starts to move, but there seems to be something wrong with the physical properties of a fixed element (obstacle), because it looks like there is no gravity for the element.

Compared to the version 2022.2.1 I had to make the following changes, otherwise an error is thrown:

Version 2022.2.1

def get_concrete_ceiling(self):
        #TODO move the path of the model to the config file
        concreteBlockPath = "pathTo/Ceiling_Obstacles.usd"
        concreteBlockPrim = create_prim(prim_path=self.default_zero_env_path + "/Concrete_Block",
                                    scale=np.array([1.0, 1.0, 1.0]), #as numpy array
                                    usd_path=concreteBlockPath,
                                    translation=[-0.625, -1.25 ,0.0], 
                                    orientation=[0.0, 0.0, 0.0, 0.0]) #returns a Usd.prim
        #convert the prim to a XForm object
        concreteBlock = XFormPrim(concreteBlockPrim.GetPath())

        self._sim_config.apply_articulation_settings("Concrete_Block", get_prim_at_path(concreteBlock.prim_path), self._sim_config.parse_actor_config("Concrete_Block"))

Version 2023.1.0

def get_concrete_ceiling(self):
        concreteBlockPath = "pathTo/Ceiling_Obstacles.usd"
        mesh_path = self.default_zero_env_path + "/Concrete_Block"
        add_reference_to_stage(concreteBlockPath, mesh_path)

        concreteBlock = RigidPrim(prim_path=self.default_zero_env_path + "/Concrete_Block",
                                scale=np.array([1.0, 1.0, 1.0]), #as numpy array
                                translation=[-0.625, -1.25 ,0.0], 
                                orientation=[0.0, 0.0, 0.0, 0.0]) #returns a Usd.prim

        self._sim_config.apply_articulation_settings("Concrete_Block", concreteBlock.prim, self._sim_config.parse_actor_config("Concrete_Block"))

Is it possible that this change creates an error, and are there other ways to integrate a fixed obstacle?

Many thanks

Milad-Rakhsha commented 8 months ago

I suspect you might need to add some contact schema to your prims for contact APIs to work properly, but I can't be sure without seeing more details. The main difference between what you have with 2023 and the previous version is that rigidPrim adds some rigid body apis to the prims but you just had an xform with the previous version. Why can't you use geometry prim if you need a static collider but not a rigid body? you might want to checkout prepare_contact_sensors contractor parameter for some details

robinvetsch commented 8 months ago

I suspect you might need to add some contact schema to your prims for contact APIs to work properly, but I can't be sure without seeing more details. The main difference between what you have with 2023 and the previous version is that rigidPrim adds some rigid body apis to the prims but you just had an xform with the previous version. Why can't you use geometry prim if you need a static collider but not a rigid body? you might want to checkout prepare_contact_sensors contractor parameter for some details

Could you email me at robin.vetsch@ost.ch and I can provide you with more information and code.

Many thanks

sujitvasanth commented 8 months ago

I encoutered similar errors - so you could try what worked for me which is on the same lines to Milad-Rakhsha's comment: try to make sure that contact reporter (API) attribute to the appropriate rigid bodies in the usd file of your robot You can do this by inspecting the usd file in isaac gym which does allow you to add this attribute if its not present alternatively you can specify your old version of the usd file in your robot/articulations/*.py to make sure this isnt the problem Screenshot from 2023-11-04 13-41-17