| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| |
|
| | |
| |
|
| | #include <vector> |
| |
|
| | #include <benchmark/benchmark.h> |
| | #include <absl/base/attributes.h> |
| | #include <mujoco/mjdata.h> |
| | #include <mujoco/mjmodel.h> |
| | #include <mujoco/mujoco.h> |
| | #include "test/fixture.h" |
| |
|
| | namespace mujoco { |
| | namespace { |
| |
|
| | |
| | static const int kNumWarmupSteps = 500; |
| |
|
| | |
| | static const int kNumBenchmarkSteps = 50; |
| |
|
| | static void run_step_benchmark(const mjModel* model, benchmark::State& state) { |
| | mjData* data = mj_makeData(model); |
| |
|
| | |
| | int nsteps = kNumWarmupSteps+kNumBenchmarkSteps; |
| | std::vector<mjtNum> ctrl = GetCtrlNoise(model, nsteps); |
| |
|
| | |
| | for (int i=0; i < kNumWarmupSteps; i++) { |
| | mju_copy(data->ctrl, ctrl.data()+model->nu*i, model->nu); |
| | mj_step(model, data); |
| | } |
| |
|
| | |
| | int spec = mjSTATE_INTEGRATION; |
| | int size = mj_stateSize(model, spec); |
| | std::vector<mjtNum> initial_state(size); |
| | mj_getState(model, data, initial_state.data(), spec); |
| |
|
| | |
| | while (state.KeepRunningBatch(kNumBenchmarkSteps)) { |
| | mj_setState(model, data, initial_state.data(), spec); |
| |
|
| | for (int i=0; i < kNumBenchmarkSteps; i++) { |
| | mjtNum* ctrl_data = ctrl.data()+model->nu*(i+kNumWarmupSteps); |
| | mju_copy(data->ctrl, ctrl_data, model->nu); |
| | mj_step(model, data); |
| | } |
| | } |
| |
|
| | |
| | mj_deleteData(data); |
| | state.SetItemsProcessed(state.iterations()); |
| | } |
| |
|
| | |
| | |
| | |
| |
|
| | void ABSL_ATTRIBUTE_NO_TAIL_CALL BM_StepFlagPlugin(benchmark::State& state) { |
| | MujocoErrorTestGuard guard; |
| | static mjModel* model = LoadModelFromPath("flex/flag.xml"); |
| | run_step_benchmark(model, state); |
| | } |
| | BENCHMARK(BM_StepFlagPlugin); |
| |
|
| | void ABSL_ATTRIBUTE_NO_TAIL_CALL BM_StepParticle(benchmark::State& state) { |
| | MujocoErrorTestGuard guard; |
| | static mjModel* model = LoadModelFromPath("replicate/particle.xml"); |
| | run_step_benchmark(model, state); |
| | } |
| | BENCHMARK(BM_StepParticle); |
| |
|
| | void ABSL_ATTRIBUTE_NO_TAIL_CALL BM_StepFlag(benchmark::State& state) { |
| | MujocoErrorTestGuard guard; |
| | static mjModel* model = |
| | LoadModelFromPath("../test/benchmark/testdata/flag.xml"); |
| | run_step_benchmark(model, state); |
| | } |
| | BENCHMARK(BM_StepFlag); |
| |
|
| | void ABSL_ATTRIBUTE_NO_TAIL_CALL BM_StepHumanoid(benchmark::State& state) { |
| | MujocoErrorTestGuard guard; |
| | static mjModel* model = LoadModelFromPath("humanoid/humanoid.xml"); |
| | run_step_benchmark(model, state); |
| | } |
| | BENCHMARK(BM_StepHumanoid); |
| |
|
| | void ABSL_ATTRIBUTE_NO_TAIL_CALL BM_StepHumanoid100(benchmark::State& state) { |
| | MujocoErrorTestGuard guard; |
| | static mjModel* model = LoadModelFromPath("humanoid/humanoid100.xml"); |
| | run_step_benchmark(model, state); |
| | } |
| | BENCHMARK(BM_StepHumanoid100); |
| |
|
| | } |
| | } |
| |
|