File size: 3,637 Bytes
2c55b92
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
// Copyright 2021 DeepMind Technologies Limited
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
//     http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#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 {

// number of steps to roll out before benchmarking
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;             // use CG solver
  model->opt.enableflags |= mjENBL_ISLAND;  // enable islands

  mjData* data = mj_makeData(model);
  mjThreadPool* threadpool = mju_threadPoolCreate(10);
  mju_bindThreadPool(data, threadpool);

  // warm-up rollout to get a steady state
  for (int i = 0; i < kNumWarmupSteps; i++) {
    mj_step(model, data);
  }

  // save the initial state and step
  int spec = mjSTATE_INTEGRATION;
  int size = mj_stateSize(model, spec);
  std::vector<mjtNum> initial_state(size);
  mj_getState(model, data, initial_state.data(), spec);

  // note: this tests resetting and stepping
  for (int i = 0; i < 10; ++i) {
    // reset to the saved state, step again, get the resulting state
    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;             // use CG solver
  model->opt.enableflags |= mjENBL_ISLAND;  // enable islands

  mjData* data = mj_makeData(model);
  mjThreadPool* threadpool = mju_threadPoolCreate(10);
  mju_bindThreadPool(data, threadpool);

  // warm-up rollout to get a steady state
  for (int i = 0; i < kNumWarmupSteps; i++) {
    mj_step(model, data);
  }

  // save the initial state and step
  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);

  // note: this tests resetting and stepping
  for (int i = 0; i < 10; ++i) {
    // reset to the saved state, step again, get the resulting state
    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);
}  // namespace
}  // namespace mujoco