Skip to content

Commit 1c69e64

Browse files
yuvaltassacopybara-github
authored andcommitted
Extend test comparing dense and sparse pipelines to all solvers.
PiperOrigin-RevId: 712862658 Change-Id: Ieb8515d32a225a098ab96055598a5d56bad7e476
1 parent 674d227 commit 1c69e64

File tree

1 file changed

+21
-15
lines changed

1 file changed

+21
-15
lines changed

test/pipeline_test.cc

Lines changed: 21 additions & 15 deletions
Original file line numberDiff line numberDiff line change
@@ -31,32 +31,38 @@ static const char* const kDefaultModel = "testdata/model.xml";
3131

3232
using ::testing::Pointwise;
3333
using ::testing::DoubleNear;
34+
using ::testing::NotNull;
3435
using PipelineTest = MujocoTest;
3536

3637

37-
// Joint and actuator damping should integrate identically under implicit
38+
// sparse and dense pipelines should produce the same results, for all solvers
3839
TEST_F(PipelineTest, SparseDenseEquivalent) {
3940
const std::string xml_path = GetTestDataFilePath(kDefaultModel);
4041
char error[1024];
4142
mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, error, sizeof(error));
42-
ASSERT_NE(model, nullptr) << error;
43+
ASSERT_THAT(model, NotNull()) << error;
4344
mjData* data = mj_makeData(model);
4445

45-
// set dense jacobian, call mj_forward, save accelerations
46-
model->opt.jacobian = mjJAC_DENSE;
47-
mj_forward(model, data);
48-
std::vector<mjtNum> qacc_dense = AsVector(data->qacc, model->nv);
46+
mjtNum tol = 1e-11;
4947

50-
// set sparse jacobian, call mj_forward, save accelerations
51-
model->opt.jacobian = mjJAC_SPARSE;
52-
mj_forward(model, data);
53-
std::vector<mjtNum> qacc_sparse = AsVector(data->qacc, model->nv);
48+
for (mjtSolver solver : {mjSOL_NEWTON, mjSOL_PGS, mjSOL_CG}) {
49+
model->opt.solver = solver;
5450

55-
// expect accelerations to be insignificantly different
56-
mjtNum tol = 1e-11;
57-
EXPECT_THAT(qacc_dense, Pointwise(DoubleNear(tol), qacc_sparse));
58-
// TODO: is 1e-12 larger than we expect?
59-
// investigate sources of discrepancy, eliminate if possible
51+
// set dense jacobian, call mj_forward, save accelerations
52+
model->opt.jacobian = mjJAC_DENSE;
53+
mj_resetDataKeyframe(model, data, 0);
54+
mj_forward(model, data);
55+
std::vector<mjtNum> qacc_dense = AsVector(data->qacc, model->nv);
56+
57+
// set sparse jacobian, call mj_forward, save accelerations
58+
model->opt.jacobian = mjJAC_SPARSE;
59+
mj_resetDataKeyframe(model, data, 0);
60+
mj_forward(model, data);
61+
std::vector<mjtNum> qacc_sparse = AsVector(data->qacc, model->nv);
62+
63+
// expect accelerations to be insignificantly different
64+
EXPECT_THAT(qacc_dense, Pointwise(DoubleNear(tol), qacc_sparse));
65+
}
6066

6167
mj_deleteData(data);
6268
mj_deleteModel(model);

0 commit comments

Comments
 (0)