-
Notifications
You must be signed in to change notification settings - Fork 1.4k
Expand file tree
/
Copy pathengine_solver_test.cc
More file actions
290 lines (244 loc) · 10.2 KB
/
engine_solver_test.cc
File metadata and controls
290 lines (244 loc) · 10.2 KB
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
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
// Copyright 2023 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.
// Tests for engine/engine_solver.c
#include <algorithm>
#include <cstdlib>
#include <string>
#include <gmock/gmock.h>
#include <gtest/gtest.h>
#include <mujoco/mujoco.h>
#include "test/fixture.h"
namespace mujoco {
namespace {
using ::testing::NotNull;
using ::testing::Pointwise;
using ::std::max;
using SolverTest = MujocoTest;
static const char* const kModelPath = "engine/testdata/solver/model.xml";
static const char* const kHumanoidPath = "engine/testdata/solver/humanoid.xml";
// compare accelerations produced by CG solver with and without islands
TEST_F(SolverTest, IslandsEquivalent) {
const std::string xml_path = GetTestDataFilePath(kModelPath);
char error[1024];
mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, error, sizeof(error));
ASSERT_THAT(model, NotNull()) << error;
model->opt.solver = mjSOL_CG; // use CG solver
model->opt.jacobian = mjJAC_SPARSE; // use sparse
model->opt.tolerance = 0; // set tolerance to 0
model->opt.ls_tolerance = 0; // set ls_tolerance to 0
model->opt.ccd_tolerance = 0; // set ccd_tolerance to 0
int nv = model->nv;
int state_size = mj_stateSize(model, mjSTATE_INTEGRATION);
mjtNum* state = (mjtNum*) mju_malloc(sizeof(mjtNum)*state_size);
mjData* data_island = mj_makeData(model);
mjData* data_noisland = mj_makeData(model);
// Below are 3 tolerances associated with 3 different iteration counts,
// they are only moderately tight, 12x higher than x86-64 failure on Linux,
// i.e. in that case the test fails with rtol smaller than {6e-3, 6e-4, 6e-5}.
// The point of this test is to show that CG convergence is actually not very
// precise, simply changing whether islands are used changes the solution by
// quite a lot, even at high iteration count and zero {ls_}tolerance.
// Increasing the iteration count higher than 60 does not improve convergence.
constexpr int kNumTol = 3;
mjtNum maxiter[kNumTol] = {30, 40, 60};
mjtNum rtol[kNumTol] = {6e-2, 6e-3, 6e-4};
for (int i = 0; i < kNumTol; ++i) {
model->opt.iterations = maxiter[i];
model->opt.ls_iterations = maxiter[i];
for (bool coldstart : {true, false}) {
mj_resetDataKeyframe(model, data_noisland, 0);
if (coldstart) {
model->opt.disableflags |= mjDSBL_WARMSTART;
} else {
model->opt.disableflags &= ~mjDSBL_WARMSTART;
}
while (data_noisland->time < .1) {
mj_getState(model, data_noisland, state, mjSTATE_INTEGRATION);
mj_setState(model, data_island, state, mjSTATE_INTEGRATION);
model->opt.disableflags &= ~mjDSBL_ISLAND; // enable islands
mj_forward(model, data_island);
model->opt.disableflags |= mjDSBL_ISLAND; // disable islands
mj_forward(model, data_noisland);
for (int j = 0; j < nv; j++) {
// increase tolerance for large elements
mjtNum scale = 0.5 * max(static_cast<mjtNum>(2.0),
std::abs(data_noisland->qacc[j]) +
std::abs(data_island->qacc[j]));
EXPECT_NEAR(data_noisland->qacc[j], data_island->qacc[j],
MjTol(scale * rtol[i], 500 * scale * rtol[i]))
<< "time: " << data_noisland->time << '\n'
<< "dof: " << j << '\n'
<< "maxiter: " << maxiter[i] << '\n'
<< "rtol: " << scale * rtol[i];
}
mj_step(model, data_noisland);
}
}
}
mj_deleteData(data_noisland);
mj_deleteData(data_island);
mju_free(state);
mj_deleteModel(model);
}
// compare accelerations produced by CG/Newton solver with and without islands
TEST_F(SolverTest, IslandsEquivalentForward) {
const std::string xml_path = GetTestDataFilePath(kModelPath);
char error[1024];
mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, error, sizeof(error));
ASSERT_THAT(model, NotNull()) << error;
int nv = model->nv;
// set tolerance to 0 so opt.iterations are always run
model->opt.tolerance = 0;
mjData* data_island = mj_makeData(model);
mjData* data_noisland = mj_makeData(model);
for (bool warmstart : {false, true}) {
for (mjtJacobian jacobian : {mjJAC_DENSE, mjJAC_SPARSE}) {
for (mjtSolver solver : {mjSOL_CG, mjSOL_NEWTON}) {
for (mjtCone cone : {mjCONE_PYRAMIDAL, mjCONE_ELLIPTIC}) {
if (warmstart) {
model->opt.disableflags &= ~mjDSBL_WARMSTART;
} else {
model->opt.disableflags |= mjDSBL_WARMSTART;
}
model->opt.jacobian = jacobian;
model->opt.solver = solver;
model->opt.cone = cone;
// disable islands, reset and step both datas to populate warmstart
model->opt.disableflags |= mjDSBL_ISLAND;
mj_resetDataKeyframe(model, data_island, 0);
mj_resetDataKeyframe(model, data_noisland, 0);
mj_step(model, data_island);
mj_step(model, data_noisland);
// forward with islands disabled
mj_forward(model, data_noisland);
// forward with islands enabled
model->opt.disableflags &= ~mjDSBL_ISLAND; // enable islands
mj_forward(model, data_island);
mjtNum scale = 0.5 * (mju_norm(data_noisland->qacc, nv) +
mju_norm(data_island->qacc, nv));
mjtNum tol = scale * (solver == mjSOL_CG ? 1e-6 : 1e-8);
EXPECT_THAT(AsVector(data_island->qacc, nv),
Pointwise(MjNear(scale * tol, 500 * scale * tol),
AsVector(data_noisland->qacc, nv)))
<< "warmstart: " << warmstart << '\n'
<< "jacobian: " << (jacobian ? "sparse" : "dense") << '\n'
<< "solver: " << (solver == mjSOL_CG ? "CG" : "Newton") << '\n'
<< "cone: " << (cone == 1 ? "elliptic" : "pyramidal");
}
}
}
}
mj_deleteData(data_noisland);
mj_deleteData(data_island);
mj_deleteModel(model);
}
TEST_F(SolverTest, SolversEquivalent) {
struct SolverTolerances {
double newton;
double cg;
double pgs_pyramidal;
double pgs_elliptic;
};
// Base relative tolerances are factor of 10 above failure thresholds
// on Linux, clang, x86-64 (i.e., test just passes with tol_multiplier = 1)
// TODO: Get float32 tolerances
const struct {
const char* path;
SolverTolerances tolerances;
} kConfigs[] = {
{.path = kModelPath,
.tolerances =
{
.newton = 1e-15,
.cg = 1e-7,
.pgs_pyramidal = 1e-14,
.pgs_elliptic = 1e-3,
}},
{.path = kHumanoidPath,
.tolerances =
{
.newton = 1e-15,
.cg = 1e-7,
.pgs_pyramidal = 1e-6,
.pgs_elliptic = 1e-9,
}},
};
for (const auto& config : kConfigs) {
const std::string xml_path = GetTestDataFilePath(config.path);
char error[1024];
mjModel* model =
mj_loadXML(xml_path.c_str(), nullptr, error, sizeof(error));
ASSERT_THAT(model, NotNull()) << error;
model->opt.tolerance = 0; // set tolerance to 0
model->opt.iterations = 500; // set iterations to 500
model->opt.disableflags |= mjDSBL_WARMSTART; // disable warmstart
int nv = model->nv;
mjData* data = mj_makeData(model);
mjData* data_truth = mj_makeData(model);
for (mjtCone cone : {mjCONE_PYRAMIDAL, mjCONE_ELLIPTIC}) {
model->opt.cone = cone;
// use Newton Dense as ground truth
model->opt.solver = mjSOL_NEWTON;
model->opt.jacobian = mjJAC_DENSE;
mj_resetDataKeyframe(model, data_truth, 0);
mj_forward(model, data_truth);
mjtNum scale = mju_norm(data_truth->qfrc_constraint, nv);
for (mjtSolver solver : {mjSOL_NEWTON, mjSOL_CG, mjSOL_PGS}) {
double rtol;
switch (solver) {
case mjSOL_NEWTON:
rtol = config.tolerances.newton;
break;
case mjSOL_CG:
rtol = config.tolerances.cg;
break;
case mjSOL_PGS:
rtol = cone == mjCONE_PYRAMIDAL ? config.tolerances.pgs_pyramidal
: config.tolerances.pgs_elliptic;
break;
}
// increase base tolerance to avoid test flakiness
double tol_multiplier = 1e2;
double tolerance = scale * rtol * tol_multiplier;
for (mjtJacobian jacobian : {mjJAC_DENSE, mjJAC_SPARSE}) {
model->opt.solver = solver;
model->opt.jacobian = jacobian;
mj_resetDataKeyframe(model, data, 0);
mj_forward(model, data);
const char* cone_str =
(cone == mjCONE_PYRAMIDAL ? "pyramidal" : "elliptic");
const char* solver_str =
(solver == mjSOL_NEWTON ? "Newton"
: (solver == mjSOL_CG ? "CG" : "PGS"));
const char* jacobian_str =
(jacobian == mjJAC_DENSE ? "dense" : "sparse");
EXPECT_THAT(AsVector(data->qfrc_constraint, nv),
Pointwise(MjNear(tolerance,
max(1e-1, 1000 * tolerance)),
AsVector(data_truth->qfrc_constraint, nv)))
<< "model: " << config.path << "\n"
<< "cone: " << cone_str << "\n"
<< "solver: " << solver_str << "\n"
<< "jacobian: " << jacobian_str << "\n"
<< "tolerance: " << tolerance;
}
}
}
mj_deleteData(data_truth);
mj_deleteData(data);
mj_deleteModel(model);
}
}
} // namespace
} // namespace mujoco