| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
| |
|
|
| |
|
|
| #include <string> |
| #include <vector> |
|
|
| #include <gmock/gmock.h> |
| #include <gtest/gtest.h> |
| #include <mujoco/mjmodel.h> |
| #include <mujoco/mujoco.h> |
| #include "src/engine/engine_io.h" |
| #include "test/fixture.h" |
|
|
| namespace mujoco { |
| namespace { |
|
|
| static const char* const kDefaultModel = "testdata/model.xml"; |
|
|
| using ::testing::Pointwise; |
| using ::testing::DoubleNear; |
| using ::testing::NotNull; |
| using PipelineTest = MujocoTest; |
|
|
|
|
| |
| TEST_F(PipelineTest, SparseDenseEquivalent) { |
| const std::string xml_path = GetTestDataFilePath(kDefaultModel); |
| char error[1024]; |
| mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, error, sizeof(error)); |
| ASSERT_THAT(model, NotNull()) << error; |
| mjData* data = mj_makeData(model); |
|
|
| mjtNum tol = 1e-11; |
|
|
| const char* sname[4] = {"NEWTON", "PGS", "CG", "NOSLIP"}; |
| mjtSolver solver[4] = {mjSOL_NEWTON, mjSOL_PGS, mjSOL_CG, mjSOL_NEWTON}; |
|
|
| for (int i : {0, 1, 2, 3}) { |
| model->opt.solver = solver[i]; |
| if (i == 3) { |
| model->opt.noslip_iterations = 2; |
| } |
|
|
| |
| model->opt.jacobian = mjJAC_DENSE; |
| mj_resetDataKeyframe(model, data, 0); |
| mj_step(model, data); |
| std::vector<mjtNum> qacc_dense = AsVector(data->qacc, model->nv); |
| std::vector<mjtNum> qpos_dense = AsVector(data->qpos, model->nq); |
|
|
| |
| model->opt.jacobian = mjJAC_SPARSE; |
| mj_resetDataKeyframe(model, data, 0); |
| mj_step(model, data); |
| std::vector<mjtNum> qacc_sparse = AsVector(data->qacc, model->nv); |
| std::vector<mjtNum> qpos_sparse = AsVector(data->qpos, model->nq); |
|
|
| |
| EXPECT_THAT(qacc_dense, Pointwise(DoubleNear(tol), qacc_sparse)) |
| << "failed qacc equivalence for solver=" << sname[i]; |
| |
| EXPECT_THAT(qpos_dense, Pointwise(DoubleNear(tol), qpos_sparse)) |
| << "failed qpos equivalence for solver=" << sname[i]; |
| } |
|
|
| mj_deleteData(data); |
| mj_deleteModel(model); |
| } |
|
|
| |
| TEST_F(PipelineTest, DeterministicNoWarmstart) { |
| const std::string xml_path = GetTestDataFilePath(kDefaultModel); |
| mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, nullptr, 0); |
| mjData* data = mj_makeData(model); |
| mjData* data2 = mj_makeData(model); |
|
|
| |
| model->opt.disableflags |= mjDSBL_WARMSTART; |
|
|
| int nv = model->nv; |
|
|
| int kNumSteps = 50; |
|
|
| for (mjtSolver solver : {mjSOL_NEWTON, mjSOL_PGS, mjSOL_CG}) { |
| model->opt.solver = solver; |
| mj_resetData(model, data); |
| mj_resetData(model, data2); |
|
|
| for (int step = 0; step < kNumSteps; step++) { |
| mj_step(model, data); |
| mj_forward(model, data); |
|
|
| mj_step(model, data2); |
| mj_forward(model, data2); |
|
|
| |
| EXPECT_EQ(AsVector(data->qacc, nv), AsVector(data2->qacc, nv)); |
|
|
| |
| mj_forward(model, data2); |
|
|
| |
| EXPECT_EQ(AsVector(data->qacc, nv), AsVector(data2->qacc, nv)); |
| } |
| } |
|
|
| mj_deleteData(data2); |
| mj_deleteData(data); |
| mj_deleteModel(model); |
| } |
|
|
|
|
| } |
| } |
|
|