isaac-sim / OmniIsaacGymEnvs

Reinforcement Learning Environments for Omniverse Isaac Gym
Other
815 stars 209 forks source link

Training speed is more than 10x slower when trying to get contact information #68

Open WSH95 opened 1 year ago

WSH95 commented 1 year ago

Hello, when I ran the training example of AnymalTerrain, I found that if I set the disable_contact_processing in the configuration file AnymalTerrain.yaml to False, the training speed dropped from about 60k fps to about 4k fps. I run the program on my computer desktop, the computer system is Ubuntu 20.04, the CPU is AMD Ryzen 7950x, and the GPU is Nvidia GeForce RTX 4090. The commands I run in the terminal are as follows: $ python scripts/rlgames_train.py task=AnymalTerrain num_envs=2048 headless=True.

I further found the code in anymal_terrain.py that makes the training slower as follows: https://github.com/NVIDIA-Omniverse/OmniIsaacGymEnvs/blob/220d34c6b68d3f7518c4aa008ae009d13cc60c03/omniisaacgymenvs/tasks/anymal_terrain.py#L220 this function is defined in omniisaacgymenvs/robots/articulations/anymal.py https://github.com/NVIDIA-Omniverse/OmniIsaacGymEnvs/blob/220d34c6b68d3f7518c4aa008ae009d13cc60c03/omniisaacgymenvs/robots/articulations/anymal.py#L100-L107

Then I commented out this line in anymal_terrain.py. In order to make the program run without error, I modified self._anymals = AnymalView(prim_paths_expr="/World/envs/.*/anymal", name="anymal_view", track_contact_forces=True) to self._anymals = AnymalView(prim_paths_expr="/World/envs/.*/anymal", name="anymal_view", track_contact_forces=True, prepare_contact_sensors=True), which is in function set_up_scene(self, scene): https://github.com/NVIDIA-Omniverse/OmniIsaacGymEnvs/blob/220d34c6b68d3f7518c4aa008ae009d13cc60c03/omniisaacgymenvs/tasks/anymal_terrain.py#L192-L200

After done this, the training speed was back to about 60k fps. But this speed is still much slower than the speed of running anymal_terrain.py in IsaacGym_Preview_4, under the same parameter configuration. In IsaacGym_Preview_4, I got about 100k fps.

I have the following questions:

  1. Will my modification get the contact force correctly?
  2. Why does anymal.prepare_contacts(self._stage, anymal.prim) make training extremely slow?
  3. Why is this example training slower than the same training in IsaacGym_Preview_4?

Thanks in advance!!

kellyguo11 commented 1 year ago

Hi there, the new contact API in Isaac Sim is an improved version of the net contact force API we had available in IsaacGym Preview 4. The new API allows for filtering between bodies, which unfortunately comes with some performance costs. When using the contact APIs in Isaac Sim, make sure disable_contact_processing is set to True. This will bypass additional processing in physics that are not needed with the tensorized APIs. prepare_contacts is a utility that applies the proper physics parameters to the bodies in order for contacts to be registered correctly.

sujitvasanth commented 12 months ago

thankyou - was a massive improvement in speed by using disable_contact_processing : True I was able to go from 128 robots to 1024 in real time...and as you say now more efficient the isaacgym preview 3 still only using minimal resources on my 3090... how can I draw more?

larsrpe commented 10 months ago

Hi, thanks for the insight Kelly and Sujit! What is conceptually the difference between tracking contact forces(and preparing contact sensors) on prims and using the contact report API? Both in terms of performance and utility.