Skip to content

Instantly share code, notes, and snippets.

@breakds
Last active July 17, 2023 22:22
Show Gist options
  • Star 0 You must be signed in to star a gist
  • Fork 0 You must be signed in to fork a gist
  • Save breakds/14fdbbfc911177dacfefaa7439eab5c1 to your computer and use it in GitHub Desktop.
Save breakds/14fdbbfc911177dacfefaa7439eab5c1 to your computer and use it in GitHub Desktop.

Go1 on Flat Ground

Test command

$ testspeed ~/projects/Hobot/hobot/environments/mj_models/go1/scene.xml 100000 20

Where 20 means using 20 (asynchronous) threads.

Ryzen 9 5950x

Running 100000 steps per thread at dt = 0.005 ...

Summary for all 20 threads

 Total simulation time  : 8.71 s
 Total steps per second : 229735
 Total realtime factor  : 1148.68 x
 Total time per step    : 4.4 µs

Details for thread 0

 Simulation time      : 8.55 s
 Steps per second     : 11701
 Realtime factor      : 58.51 x
 Time per step        : 85.5 µs

 Broadphase accuracy  : 99.98%
 Midphase accuracy    : 99.98%
 Contacts per step    : 4.00
 Constraints per step : 29.98
 Degrees of freedom   : 18

 Internal profiler for thread 0 (µs per step)
             step :   85.3  (100.00 %)
          forward :   84.0  ( 98.42 %)
         position :   30.5  ( 35.78 %)
         velocity :    1.8  (  2.12 %)
        actuation :    0.3  (  0.39 %)
     acceleration :    0.4  (  0.51 %)
       constraint :   49.0  ( 57.39 %)
   pos_kinematics :    3.0  (  3.51 %)
      pos_inertia :    1.5  (  1.79 %)
    pos_collision :   22.3  ( 26.14 %)
         pos_make :    3.5  (  4.09 %)
      pos_project :    0.0  (  0.04 %)
            other :    3.2  (  3.80 %)

Ryzen 9 7950x

Running 100000 steps per thread at dt = 0.005 ...

Summary for all 20 threads

 Total simulation time  : 6.75 s
 Total steps per second : 296229
 Total realtime factor  : 1481.15 x
 Total time per step    : 3.4 µs

Details for thread 0

 Simulation time      : 4.87 s
 Steps per second     : 20536
 Realtime factor      : 102.68 x
 Time per step        : 48.7 µs

 Broadphase accuracy  : 99.98%
 Midphase accuracy    : 99.98%
 Contacts per step    : 4.00
 Constraints per step : 29.98
 Degrees of freedom   : 18

 Internal profiler for thread 0 (µs per step)
             step :   48.6  (100.00 %)
          forward :   47.9  ( 98.56 %)
         position :   15.0  ( 30.84 %)
         velocity :    0.9  (  1.92 %)
        actuation :    0.2  (  0.33 %)
     acceleration :    0.2  (  0.50 %)
       constraint :   30.6  ( 62.95 %)
   pos_kinematics :    1.6  (  3.24 %)
      pos_inertia :    0.8  (  1.55 %)
    pos_collision :   10.8  ( 22.28 %)
         pos_make :    1.7  (  3.45 %)
      pos_project :    0.0  (  0.05 %)
            other :    1.7  (  3.44 %)

Threadripper PRO 5975WX

Running 100000 steps per thread at dt = 0.005 ...

Summary for all 20 threads

 Total simulation time  : 6.43 s
 Total steps per second : 310905
 Total realtime factor  : 1554.52 x
 Total time per step    : 3.2 µs

Details for thread 0

 Simulation time      : 6.20 s
 Steps per second     : 16139
 Realtime factor      : 80.70 x
 Time per step        : 62.0 µs

 Broadphase accuracy  : 99.98%
 Midphase accuracy    : 99.98%
 Contacts per step    : 4.00
 Constraints per step : 29.98
 Degrees of freedom   : 18

 Internal profiler for thread 0 (µs per step)
             step :   61.8  (100.00 %)
          forward :   60.9  ( 98.51 %)
         position :   21.1  ( 34.10 %)
         velocity :    1.2  (  1.93 %)
        actuation :    0.2  (  0.34 %)
     acceleration :    0.3  (  0.54 %)
       constraint :   36.8  ( 59.55 %)
   pos_kinematics :    2.1  (  3.39 %)
      pos_inertia :    1.0  (  1.55 %)
    pos_collision :   15.6  ( 25.19 %)
         pos_make :    2.3  (  3.64 %)
      pos_project :    0.0  (  0.05 %)
            other :    2.2  (  3.55 %)

With 32 threads:

Running 100000 steps per thread at dt = 0.005 ...

Summary for all 32 threads

 Total simulation time  : 6.53 s
 Total steps per second : 490144
 Total realtime factor  : 2450.72 x
 Total time per step    : 2.0 µs

Details for thread 0

 Simulation time      : 6.30 s
 Steps per second     : 15880
 Realtime factor      : 79.40 x
 Time per step        : 63.0 µs

 Broadphase accuracy  : 99.98%
 Midphase accuracy    : 99.98%
 Contacts per step    : 4.00
 Constraints per step : 29.98
 Degrees of freedom   : 18

 Internal profiler for thread 0 (µs per step)
             step :   62.8  (100.00 %)
          forward :   61.9  ( 98.54 %)
         position :   21.6  ( 34.40 %)
         velocity :    1.2  (  1.91 %)
        actuation :    0.2  (  0.34 %)
     acceleration :    0.3  (  0.50 %)
       constraint :   37.3  ( 59.44 %)
   pos_kinematics :    2.1  (  3.40 %)
      pos_inertia :    1.0  (  1.55 %)
    pos_collision :   16.0  ( 25.39 %)
         pos_make :    2.4  (  3.74 %)
      pos_project :    0.0  (  0.04 %)
            other :    2.2  (  3.43 %)

Go1 with Terrain

Test command

$ testspeed ~/projects/Hobot/hobot/environments/mj_models/go1/scene.xml 100000 20

Ryzen 9 5950x

Running 1000 steps per thread at dt = 0.005 ...

Summary for all 16 threads

 Total simulation time  : 0.87 s
 Total steps per second : 18315
 Total realtime factor  : 91.58 x
 Total time per step    : 54.6 µs

Details for thread 0

 Simulation time      : 0.70 s
 Steps per second     : 1435
 Realtime factor      : 7.18 x
 Time per step        : 696.7 µs

 Broadphase accuracy  : 28.67%
 Midphase accuracy    : 14.91%
 Contacts per step    : 33.73
 Constraints per step : 213.65
 Degrees of freedom   : 18

 Internal profiler for thread 0 (µs per step)
             step :  696.6  (100.00 %)
          forward :  695.5  ( 99.85 %)
         position :  157.6  ( 22.62 %)
         velocity :    2.0  (  0.29 %)
        actuation :    0.2  (  0.04 %)
     acceleration :    0.4  (  0.05 %)
       constraint :  533.2  ( 76.55 %)
   pos_kinematics :    2.3  (  0.32 %)
      pos_inertia :    1.0  (  0.14 %)
    pos_collision :  141.7  ( 20.35 %)
         pos_make :   12.4  (  1.77 %)
      pos_project :    0.0  (  0.00 %)
            other :    3.2  (  0.46 %)

Humanoid

Ryzen 9 5950x

Running 100000 steps per thread at dt = 0.005 ...

Summary for all 20 threads

 Total simulation time  : 4.60 s
 Total steps per second : 434324
 Total realtime factor  : 2171.62 x
 Total time per step    : 2.3 µs

Details for thread 0

 Simulation time      : 4.46 s
 Steps per second     : 22397
 Realtime factor      : 111.99 x
 Time per step        : 44.6 µs

 Broadphase accuracy  : 50.72%
 Midphase accuracy    : 47.62%
 Contacts per step    : 12.55
 Constraints per step : 48.52
 Degrees of freedom   : 27

 Internal profiler for thread 0 (µs per step)
             step :   44.5  (100.00 %)
          forward :   42.2  ( 94.80 %)
         position :   23.0  ( 51.61 %)
         velocity :    2.5  (  5.55 %)
        actuation :    0.5  (  1.02 %)
     acceleration :    0.7  (  1.56 %)
       constraint :   15.4  ( 34.55 %)
   pos_kinematics :    3.1  (  7.07 %)
      pos_inertia :    2.9  (  6.55 %)
    pos_collision :   10.4  ( 23.45 %)
         pos_make :    6.3  ( 14.08 %)
      pos_project :    0.0  (  0.07 %)
            other :    2.5  (  5.71 %)
import time
import numpy as np
from mujoco import MjModel, MjData, mju_Halton, mj_resetDataKeyframe, mj_forward, mj_step, viewer
def control_noise(model: MjModel, nsteps: int, noise: np.ndarray):
result = []
for step in range(nsteps):
for i in range(model.nu):
center = 0.0
radius = 1.0
r = model.actuator_ctrlrange + 2 * i
center = (r[:, 1] + r[:, 0]) / 2
radius = (r[:, 1] - r[:, 0]) / 2
radius *= noise
result.append(center + radius * (2 * mju_Halton(step, i + 2) - 1))
return np.array(result)
if __name__ == "__main__":
model = MjModel.from_xml_path("/home/breakds/syncthing/workspace/incoming/go1_terrain/scene.xml")
with open("/home/breakds/syncthing/workspace/incoming/debug_mujoco_performance/recorded_control.json", "r") as f:
import json
ctrl = json.load(f)
data = MjData(model)
mj_resetDataKeyframe(model, data, 0)
contacts = 0
constraints = 0
num_steps = len(ctrl)
start = time.time()
# with viewer.launch_passive(model, data) as viewer:
for i in range(num_steps):
data.ctrl = np.array(ctrl[i])
mj_step(model, data)
contacts += data.ncon
constraints += data.nefc
# if i % 4 == 0:
# time.sleep(0.02)
# with viewer.lock():
# viewer.cam.lookat = data.body("trunk").subtree_com
# viewer.sync()
time_elapsed = time.time() - start
print(f"num steps: {num_steps}")
print(f"Time elapsed: {time_elapsed}")
print(f"steps per second: {num_steps / time_elapsed}")
print(f"sim:real = {num_steps * 0.005 / (time.time() - start)}x")
print(f"contacts per step: {contacts / num_steps}")
print(f"constraints per step: {constraints / num_steps}")
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment