Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Meshes affecting simulation performance #1279

Closed
jdao913 opened this issue Dec 14, 2023 · 6 comments
Closed

Meshes affecting simulation performance #1279

jdao913 opened this issue Dec 14, 2023 · 6 comments
Assignees
Labels
question Request for help or information

Comments

@jdao913
Copy link

jdao913 commented Dec 14, 2023

Hello!

Our group has been using Mujoco for a while now our research and I recently noticed some strange performance differences when having meshes vs. not having them. We recently updated to Mujoco version 3.0.1 from 2.3.5 and noticed that our models were running a lot slower, and it seems to be caused by meshes, even though we have no mesh collisions. I found that just removing all meshes sped up performance a lot, by about 60%. Using the example testspeed profiling script I can see that this difference comes mainly from collisions; kinematics, constraints, etc. all take about the same amount of time with and without meshes.

After some version traceback it seems like something changed between versions 2.3.5 and 2.3.6. The same model will run slower in 2.3.6 than in 2.3.5, and in order to get a similar level of performance back, I have to delete all meshes.

As a minimal example, I used the Mujoco Menagerie Cassie model. For the no mesh version I just deleted all the mesh geoms and all of the meshes in asset. On my machine (AMD 5900X) testing on a single core I get the following results.

Mujoco 2.3.5, original model (with meshes)

./testspeed ~/mujoco_menagerie/agility_cassie/cassie.xml 100000 1 0.1 1

Running 100000 steps at dt = 0.0005 ...

 Simulation time      : 1.88 s
 Steps per second     : 53206
 Realtime factor      : 26.60 x
 Time per step        : 0.0188 ms

 Broadphase accuracy  : 100.00%
 Midphase accuracy    : 100.00%
 Contacts per step    : 0.00
 Constraints per step : 12.04
 Degrees of freedom   : 32

 Profiler phase (ms per step)
             step : 0.01876  (100.00 %)
          forward : 0.01726  ( 92.02 %)
         position : 0.00790  ( 42.12 %)
         velocity : 0.00140  (  7.48 %)
        actuation : 0.00013  (  0.67 %)
     acceleration : 0.00059  (  3.17 %)
       constraint : 0.00603  ( 32.14 %)
   pos_kinematics : 0.00213  ( 11.34 %)
      pos_inertia : 0.00165  (  8.79 %)
    pos_collision : 0.00295  ( 15.74 %)
         pos_make : 0.00099  (  5.28 %)
      pos_project : 0.00003  (  0.14 %)

Mujoco 2.3.5, model without meshes

./testspeed ~/mujoco_menagerie/agility_cassie/cassie-no-mesh.xml 100000 1 0.1 1

Running 100000 steps at dt = 0.0005 ...

 Simulation time      : 1.84 s
 Steps per second     : 54201
 Realtime factor      : 27.10 x
 Time per step        : 0.0184 ms

 Broadphase accuracy  : 100.00%
 Midphase accuracy    : 100.00%
 Contacts per step    : 0.00
 Constraints per step : 12.04
 Degrees of freedom   : 32

 Profiler phase (ms per step)
             step : 0.01842  (100.00 %)
          forward : 0.01662  ( 90.23 %)
         position : 0.00711  ( 38.59 %)
         velocity : 0.00141  (  7.65 %)
        actuation : 0.00014  (  0.74 %)
     acceleration : 0.00058  (  3.17 %)
       constraint : 0.00617  ( 33.49 %)
   pos_kinematics : 0.00193  ( 10.46 %)
      pos_inertia : 0.00164  (  8.90 %)
    pos_collision : 0.00235  ( 12.78 %)
         pos_make : 0.00100  (  5.44 %)
      pos_project : 0.00003  (  0.14 %)

Mujoco 2.3.6, original model (with meshes)

./testspeed ~/mujoco_menagerie/agility_cassie/cassie.xml 100000 1 0.1 1

Running 100000 steps at dt = 0.0005 ...

 Simulation time      : 2.11 s
 Steps per second     : 47445
 Realtime factor      : 23.72 x
 Time per step        : 0.0211 ms

 Broadphase accuracy  : 100.00%
 Midphase accuracy    : 100.00%
 Contacts per step    : 0.00
 Constraints per step : 12.04
 Degrees of freedom   : 32

 Profiler phase (ms per step)
             step : 0.02103  (100.00 %)
          forward : 0.01945  ( 92.47 %)
         position : 0.00987  ( 46.91 %)
         velocity : 0.00140  (  6.65 %)
        actuation : 0.00013  (  0.61 %)
     acceleration : 0.00062  (  2.95 %)
       constraint : 0.00614  ( 29.21 %)
   pos_kinematics : 0.00220  ( 10.48 %)
      pos_inertia : 0.00162  (  7.72 %)
    pos_collision : 0.00479  ( 22.75 %)
         pos_make : 0.00107  (  5.08 %)
      pos_project : 0.00003  (  0.13 %)

Mujoco 2.3.6, model without meshes

./testspeed ~/mujoco_menagerie/agility_cassie/cassie-no-mesh.xml 100000 1 0.1 1

Running 100000 steps at dt = 0.0005 ...

 Simulation time      : 1.80 s
 Steps per second     : 55482
 Realtime factor      : 27.74 x
 Time per step        : 0.0180 ms

 Broadphase accuracy  : 100.00%
 Midphase accuracy    : 100.00%
 Contacts per step    : 0.00
 Constraints per step : 12.04
 Degrees of freedom   : 32

 Profiler phase (ms per step)
             step : 0.01799  (100.00 %)
          forward : 0.01645  ( 91.43 %)
         position : 0.00706  ( 39.26 %)
         velocity : 0.00136  (  7.55 %)
        actuation : 0.00014  (  0.76 %)
     acceleration : 0.00060  (  3.31 %)
       constraint : 0.00602  ( 33.48 %)
   pos_kinematics : 0.00191  ( 10.59 %)
      pos_inertia : 0.00160  (  8.87 %)
    pos_collision : 0.00236  ( 13.14 %)
         pos_make : 0.00102  (  5.65 %)
      pos_project : 0.00003  (  0.15 %)

As can be seen the same model runs faster in version 2.3.5 than in 2.3.6, and in version 2.3.5 we get similar performance between having meshes and not having them. When removing the meshes we get 2.3.6 to perform as fast as 2.3.5, and the cause for the slow down is from the pos_collision taking double the amount of time in the mesh case.

As an extra check, here are the same tests run in current 3.0.1 version. It runs faster than in 2.3.5/2.3.6, but the difference between mesh vs. no mesh is still present. (Note that collision time is still twice as long in the mesh case vs. no mesh).

Mujoco 3.0.1, original model (with meshes)

./testspeed ~/mujoco_menagerie/agility_cassie/cassie.xml 100000 1 0.1

Rolling out 100000 steps, at dt = 0.0005...

 Simulation time      : 1.90 s
 Steps per second     : 52619
 Realtime factor      : 26.31 x
 Time per step        : 19.0 µs

 Contacts per step    : 0.00
 Constraints per step : 12.04
 Degrees of freedom   : 32

 Internal profiler, µs per step
              step :   19.0  (100.00 %)
           forward :   17.4  ( 91.92 %)
          position :    8.3  ( 43.93 %)
          velocity :    1.2  (  6.28 %)
         actuation :    0.2  (  0.84 %)
        constraint :    6.0  ( 31.45 %)
           advance :    1.4  (  7.40 %)
             other :    1.9  ( 10.10 %)

   position total  :    8.3  ( 43.93 %)
     kinematics    :    2.1  ( 11.11 %)
     inertia       :    1.6  (  8.53 %)
     collision     :    3.4  ( 17.77 %)
       broadphase  :    1.3  (  6.95 %)
       midphase    :    0.4  (  2.03 %)
       narrowphase :    0.0  (  0.00 %)
     make          :    1.0  (  5.27 %)
     project       :    0.0  (  0.14 %)

Mujoco 3.0.1, model without meshes

./testspeed ~/mujoco_menagerie/agility_cassie/cassie-no-mesh.xml 100000 1 0.1

Rolling out 100000 steps, at dt = 0.0005...

 Simulation time      : 1.73 s
 Steps per second     : 57769
 Realtime factor      : 28.88 x
 Time per step        : 17.3 µs

 Contacts per step    : 0.00
 Constraints per step : 12.04
 Degrees of freedom   : 32

 Internal profiler, µs per step
              step :   17.3  (100.00 %)
           forward :   15.7  ( 90.85 %)
          position :    6.3  ( 36.74 %)
          velocity :    1.2  (  7.08 %)
         actuation :    0.2  (  0.95 %)
        constraint :    6.1  ( 35.43 %)
           advance :    1.4  (  8.38 %)
             other :    2.0  ( 11.42 %)

   position total  :    6.3  ( 36.74 %)
     kinematics    :    1.9  ( 11.21 %)
     inertia       :    1.6  (  9.35 %)
     collision     :    1.6  (  8.99 %)
       broadphase  :    1.2  (  6.77 %)
       midphase    :    0.3  (  1.73 %)
       narrowphase :    0.0  (  0.00 %)
     make          :    1.0  (  5.80 %)
     project       :    0.0  (  0.16 %)

The only note in the changelog of 2.3.6 that I saw about meshes is a mesh bounding box and coordinate frame fix, but that doesn't seem relevant to this? Regardless, why is removing meshes affecting collision computation time even when there are no mesh collisions? I might just be stupid and missing something about how meshes work and how collision detection happens, but I don't understand what is happening here.

Thanks for any help and insight you can provide!

@jdao913 jdao913 added the question Request for help or information label Dec 14, 2023
@yuvaltassa
Copy link
Collaborator

Thanks, this is valuable! On its face meshes that do not collide should not be adding anything to runtime, your expectation is very valid. We will investigate, though probably only in the new year.

@yuvaltassa
Copy link
Collaborator

Hi @jdao913,

We've diagnosed this and the core issue is a little tricky to solve (related to Bounding Volume Hierarchies of visual meshes, which are used by raycasting).

However we have a workaround that should work well and is generally a good thing to know about. In the recently submitted 1e2e0b3, @quagla improved the compiler's discardvisual flag. Setting this flag will automatically discard all visual-only elements from the mjModel, giving you a model which simulates identically (with the exception of raycasting, see documentation above), but is much smaller and often faster to simulate.

Closing this issue for now, but feel free to comment if the above doesn't work for you.

copybara-service bot pushed a commit that referenced this issue Jan 19, 2024
PiperOrigin-RevId: 599778272
Change-Id: If5530629035cc68b198447503388f59a04041b13
@yuvaltassa
Copy link
Collaborator

The fix in fea7c10 is what you want. Added a flag to disable the visualization of active bounding volumes.

@yuvaltassa
Copy link
Collaborator

yuvaltassa commented Feb 9, 2024 via email

@P-Schumacher
Copy link

P-Schumacher commented Feb 9, 2024

Hi Yuval,
it seems I was not using the newest version of MuJoCo when I tested it. It works as intended with our models and mujoco==3.1.2.

Thank you for checking up on this.

@yuvaltassa
Copy link
Collaborator

yuvaltassa commented Feb 9, 2024 via email

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
question Request for help or information
Projects
None yet
Development

No branches or pull requests

4 participants