| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | #include <array> |
| | #include <vector> |
| |
|
| | #include <benchmark/benchmark.h> |
| | #include <mujoco/mjmodel.h> |
| | #include <mujoco/mjthread.h> |
| | #include <mujoco/mujoco.h> |
| | #include "test/fixture.h" |
| |
|
| | namespace mujoco { |
| | namespace { |
| |
|
| | |
| | static const int kNumWarmupSteps = 500; |
| |
|
| | void BM_StepHumanoid200(benchmark::State& state) { |
| | auto model_path = GetTestDataFilePath("benchmark/testdata/humanoid200.xml"); |
| | std::array<char, 1024> error; |
| | mjModel* model = |
| | mj_loadXML(model_path.c_str(), nullptr, error.data(), error.size()); |
| |
|
| | model->opt.solver = mjSOL_CG; |
| | model->opt.enableflags |= mjENBL_ISLAND; |
| |
|
| | mjData* data = mj_makeData(model); |
| | mjThreadPool* threadpool = mju_threadPoolCreate(10); |
| | mju_bindThreadPool(data, threadpool); |
| |
|
| | |
| | for (int i = 0; i < kNumWarmupSteps; i++) { |
| | 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); |
| |
|
| | |
| | for (int i = 0; i < 10; ++i) { |
| | |
| | mj_setState(model, data, initial_state.data(), spec); |
| | for (int i = 0; i < kNumWarmupSteps; i++) { |
| | mj_step(model, data); |
| | } |
| | } |
| |
|
| | state.SetItemsProcessed(state.iterations()); |
| | mj_deleteData(data); |
| | mju_threadPoolDestroy(threadpool); |
| | } |
| |
|
| | void BM_Step22Humanoids(benchmark::State& state) { |
| | auto model_path = GetTestDataFilePath("benchmark/testdata/22_humanoids.xml"); |
| | std::array<char, 1024> error; |
| | mjModel* model = |
| | mj_loadXML(model_path.c_str(), nullptr, error.data(), error.size()); |
| | model->opt.solver = mjSOL_CG; |
| | model->opt.enableflags |= mjENBL_ISLAND; |
| |
|
| | mjData* data = mj_makeData(model); |
| | mjThreadPool* threadpool = mju_threadPoolCreate(10); |
| | mju_bindThreadPool(data, threadpool); |
| |
|
| | |
| | for (int i = 0; i < kNumWarmupSteps; i++) { |
| | 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); |
| |
|
| | std::vector<mjtNum> ctrl = GetCtrlNoise(model, kNumWarmupSteps); |
| |
|
| | |
| | for (int i = 0; i < 10; ++i) { |
| | |
| | mj_setState(model, data, initial_state.data(), spec); |
| | for (int i = 0; i < kNumWarmupSteps; i++) { |
| | mju_copy(data->ctrl, ctrl.data()+model->nu*i, model->nu); |
| | mj_step(model, data); |
| | } |
| | } |
| |
|
| | state.SetItemsProcessed(state.iterations()); |
| | mj_deleteData(data); |
| | mju_threadPoolDestroy(threadpool); |
| | } |
| |
|
| | BENCHMARK(BM_StepHumanoid200); |
| | BENCHMARK(BM_Step22Humanoids); |
| | } |
| | } |
| |
|