| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| |
|
| | |
| |
|
| | #include <benchmark/benchmark.h> |
| | #include <absl/base/attributes.h> |
| | #include <mujoco/mjdata.h> |
| | #include <mujoco/mujoco.h> |
| | #include "src/engine/engine_core_smooth.h" |
| | #include "src/engine/engine_util_misc.h" |
| | #include "test/fixture.h" |
| |
|
| | namespace mujoco { |
| | namespace { |
| |
|
| | |
| | static const int kNumBenchmarkSteps = 50; |
| |
|
| | |
| |
|
| | static void BM_factorI(benchmark::State& state, bool legacy, bool coil) { |
| | static mjModel* m; |
| | if (coil) { |
| | m = LoadModelFromPath("plugin/elasticity/coil.xml"); |
| | } else { |
| | m = LoadModelFromPath("humanoid/humanoid100.xml"); |
| | } |
| |
|
| | mjData* d = mj_makeData(m); |
| | mj_forward(m, d); |
| |
|
| | |
| | mj_markStack(d); |
| |
|
| | |
| | mjtNum* M = mj_stackAllocNum(d, m->nC); |
| | mju_gather(M, d->qM, d->mapM2M, m->nC); |
| |
|
| | |
| | mjtNum* LDlegacy = mj_stackAllocNum(d, m->nM); |
| |
|
| | |
| | while (state.KeepRunningBatch(kNumBenchmarkSteps)) { |
| | for (int i=0; i < kNumBenchmarkSteps; i++) { |
| | if (legacy) { |
| | mj_factorI_legacy(m, d, d->qM, LDlegacy, d->qLDiagInv); |
| | } else { |
| | mju_copy(d->qLD, M, m->nC); |
| | mj_factorI(d->qLD, d->qLDiagInv, m->nv, |
| | d->M_rownnz, d->M_rowadr, d->M_colind); |
| | } |
| | } |
| | } |
| |
|
| | |
| | mj_freeStack(d); |
| | mj_deleteData(d); |
| | mj_deleteModel(m); |
| | state.SetItemsProcessed(state.iterations()); |
| | } |
| |
|
| | void ABSL_ATTRIBUTE_NO_TAIL_CALL |
| | BM_factorI_COIL_LEGACY(benchmark::State& state) { |
| | MujocoErrorTestGuard guard; |
| | BM_factorI(state, true, true); |
| | } |
| | BENCHMARK(BM_factorI_COIL_LEGACY); |
| |
|
| | void ABSL_ATTRIBUTE_NO_TAIL_CALL |
| | BM_factorI_COIL_CSR(benchmark::State& state) { |
| | MujocoErrorTestGuard guard; |
| | BM_factorI(state, false, true); |
| | } |
| | BENCHMARK(BM_factorI_COIL_CSR); |
| |
|
| | void ABSL_ATTRIBUTE_NO_TAIL_CALL |
| | BM_factorI_H100_LEGACY(benchmark::State& state) { |
| | MujocoErrorTestGuard guard; |
| | BM_factorI(state, true, false); |
| | } |
| | BENCHMARK(BM_factorI_H100_LEGACY); |
| |
|
| | void ABSL_ATTRIBUTE_NO_TAIL_CALL |
| | BM_factorI_H100_CSR(benchmark::State& state) { |
| | MujocoErrorTestGuard guard; |
| | BM_factorI(state, false, false); |
| | } |
| | BENCHMARK(BM_factorI_H100_CSR); |
| |
|
| | } |
| | } |
| |
|