| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| |
|
| | |
| |
|
| | #include <string> |
| | #include <vector> |
| |
|
| | #include <gmock/gmock.h> |
| | #include <gtest/gtest.h> |
| | #include <mujoco/mjmodel.h> |
| | #include <mujoco/mujoco.h> |
| | #include "src/engine/engine_island.h" |
| | #include "src/engine/engine_util_sparse.h" |
| | #include "test/fixture.h" |
| |
|
| | namespace mujoco { |
| | namespace { |
| |
|
| | using ::testing::DoubleNear; |
| | using ::testing::ElementsAre; |
| | using ::testing::Pointwise; |
| | using IslandTest = MujocoTest; |
| |
|
| |
|
| | TEST_F(IslandTest, FloodFillSingleton) { |
| | |
| | |
| | |
| | mjtNum mat[9] = { |
| | 1, 0, 0, |
| | 0, 0, 0, |
| | 0, 0, 1 |
| | }; |
| | constexpr int nr = 3; |
| | constexpr int nnz = 2; |
| | int rownnz[nr]; |
| | int rowadr[nr]; |
| | int colind[nnz]; |
| | mjtNum res[nnz]; |
| | mju_dense2sparse(res, mat, nr, nr, rownnz, rowadr, colind, nnz); |
| |
|
| | |
| | int island[nr]; |
| | int scratch[2*nr]; |
| |
|
| | |
| | int nisland = mj_floodFill(island, nr, rownnz, rowadr, colind, scratch); |
| |
|
| | EXPECT_EQ(nisland, 2); |
| | EXPECT_THAT(island, ElementsAre(0, -1, 1)); |
| | } |
| |
|
| |
|
| | TEST_F(IslandTest, FloodFill1) { |
| | |
| | mjtNum mat[9] = { |
| | 0, 1, 0, |
| | 1, 0, 1, |
| | 0, 1, 0 |
| | }; |
| | constexpr int nr = 3; |
| | constexpr int nnz = 4; |
| | int rownnz[nr]; |
| | int rowadr[nr]; |
| | int colind[nnz]; |
| | mjtNum res[nnz]; |
| | mju_dense2sparse(res, mat, nr, nr, rownnz, rowadr, colind, nnz); |
| |
|
| | |
| | int island[nr]; |
| | int stack[nnz]; |
| |
|
| | int nisland = mj_floodFill(island, nr, rownnz, rowadr, colind, stack); |
| |
|
| | EXPECT_EQ(nisland, 1); |
| | EXPECT_THAT(island, ElementsAre(0, 0, 0)); |
| | } |
| |
|
| |
|
| | TEST_F(IslandTest, FloodFill2) { |
| | |
| | mjtNum mat[49] = { |
| | 0, 0, 0, 1, 0, 0, 0, |
| | 0, 0, 0, 0, 1, 0, 1, |
| | 0, 0, 0, 0, 0, 1, 0, |
| | 1, 0, 0, 0, 0, 1, 0, |
| | 0, 1, 0, 0, 0, 0, 0, |
| | 0, 0, 1, 1, 0, 0, 0, |
| | 0, 1, 0, 0, 0, 0, 0, |
| | }; |
| | constexpr int nr = 7; |
| | constexpr int nnz = 10; |
| | int rownnz[nr]; |
| | int rowadr[nr]; |
| | int colind[nnz]; |
| | mjtNum res[nnz]; |
| | mju_dense2sparse(res, mat, nr, nr, rownnz, rowadr, colind, nnz); |
| |
|
| | |
| | int island[nr]; |
| | int stack[nnz]; |
| |
|
| | int nisland = mj_floodFill(island, nr, rownnz, rowadr, colind, stack); |
| |
|
| | EXPECT_EQ(nisland, 2); |
| | EXPECT_THAT(island, ElementsAre(0, 1, 0, 0, 1, 0, 1)); |
| | } |
| |
|
| |
|
| | TEST_F(IslandTest, FloodFill3a) { |
| | |
| | |
| | mjtNum mat[16] = { |
| | 0, 0, 0, 0, |
| | 0, 0, 0, 1, |
| | 0, 0, 1, 0, |
| | 0, 1, 0, 0, |
| | }; |
| | constexpr int nr = 4; |
| | constexpr int nnz = 3; |
| | int rownnz[nr]; |
| | int rowadr[nr]; |
| | int colind[nnz]; |
| | mjtNum res[nnz]; |
| | mju_dense2sparse(res, mat, nr, nr, rownnz, rowadr, colind, nnz); |
| |
|
| | |
| | int island[nr]; |
| | int stack[nnz]; |
| |
|
| | int nisland = mj_floodFill(island, nr, rownnz, rowadr, colind, stack); |
| |
|
| | EXPECT_EQ(nisland, 2); |
| | EXPECT_THAT(island, ElementsAre(-1, 0, 1, 0)); |
| | } |
| |
|
| |
|
| | TEST_F(IslandTest, FloodFill3b) { |
| | |
| | |
| | |
| | |
| | |
| | mjtNum mat[49] = { |
| | 0, 0, 0, 0, 1, 0, 1, |
| | 0, 1, 1, 0, 0, 0, 0, |
| | 0, 1, 0, 0, 0, 0, 0, |
| | 0, 0, 0, 0, 0, 0, 0, |
| | 1, 0, 0, 0, 0, 1, 1, |
| | 0, 0, 0, 0, 1, 0, 1, |
| | 1, 0, 0, 0, 1, 1, 0, |
| | }; |
| | constexpr int nr = 7; |
| | constexpr int nnz = 13; |
| | int rownnz[nr]; |
| | int rowadr[nr]; |
| | int colind[nnz]; |
| | mjtNum res[nnz]; |
| | mju_dense2sparse(res, mat, nr, nr, rownnz, rowadr, colind, nnz); |
| |
|
| | |
| | int island[nr]; |
| | int stack[nnz]; |
| |
|
| | int nisland = mj_floodFill(island, nr, rownnz, rowadr, colind, stack); |
| |
|
| | EXPECT_EQ(nisland, 2); |
| | EXPECT_THAT(island, ElementsAre(0, 1, 1, -1, 0, 0, 0)); |
| | } |
| |
|
| | static const char* const kAbacusPath = |
| | "engine/testdata/island/abacus.xml"; |
| |
|
| | TEST_F(IslandTest, Abacus) { |
| | const std::string xml_path = GetTestDataFilePath(kAbacusPath); |
| | mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, nullptr, 0); |
| |
|
| | |
| | model->opt.disableflags |= mjDSBL_GRAVITY; |
| |
|
| | mjData* data = mj_makeData(model); |
| | mj_forward(model, data); |
| |
|
| | |
| | EXPECT_EQ(data->nisland, 0); |
| |
|
| | |
| | data->qfrc_applied[0] = -1; |
| | data->qfrc_applied[2] = 1; |
| | while (data->ncon != 3) { |
| | mj_step(model, data); |
| | } |
| |
|
| | |
| | int nv = model->nv; |
| | int nefc = data->nefc; |
| | int nisland = data->nisland; |
| | int nidof = data->nidof; |
| |
|
| | |
| | EXPECT_EQ(nv, 4); |
| | EXPECT_EQ(nidof, 3); |
| | EXPECT_EQ(nefc, 12); |
| | EXPECT_EQ(nisland, 2); |
| |
|
| | |
| | EXPECT_THAT(AsVector(data->island_idofadr, nisland), ElementsAre(0, 1)); |
| |
|
| | |
| | EXPECT_THAT(AsVector(data->island_nv, nisland), ElementsAre(1, 2)); |
| |
|
| | |
| | |
| | |
| | EXPECT_THAT(AsVector(data->dof_island, nv), ElementsAre(0, -1, 1, 1)); |
| |
|
| | |
| | |
| | |
| | EXPECT_THAT(AsVector(data->map_idof2dof, nv), ElementsAre(0, 2, 3, 1)); |
| |
|
| | |
| | |
| | |
| | EXPECT_THAT(AsVector(data->map_dof2idof, nv), ElementsAre(0, 3, 1, 2)); |
| |
|
| | |
| | |
| | EXPECT_THAT(AsVector(data->island_iefcadr, nisland), ElementsAre(0, 4)); |
| |
|
| | |
| | EXPECT_THAT(AsVector(data->island_nefc, nisland), ElementsAre(4, 8)); |
| |
|
| | |
| | |
| | EXPECT_THAT(AsVector(data->efc_island, nefc), |
| | ElementsAre(0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1)); |
| |
|
| | |
| | EXPECT_THAT(AsVector(data->map_iefc2efc, nefc), |
| | ElementsAre(0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11)); |
| |
|
| | |
| | mj_resetData(model, data); |
| | data->qfrc_applied[0] = -1; |
| | data->qfrc_applied[1] = 1; |
| | data->qfrc_applied[2] = -1; |
| | data->qfrc_applied[3] = 1; |
| |
|
| | |
| | while (data->ncon != 3) { |
| | mj_step(model, data); |
| | } |
| |
|
| | |
| | nefc = data->nefc; |
| | nisland = data->nisland; |
| | nidof = data->nidof; |
| |
|
| | EXPECT_EQ(nisland, 3); |
| | EXPECT_EQ(nidof, 4); |
| | EXPECT_THAT(AsVector(data->island_idofadr, nisland), ElementsAre(0, 1, 3)); |
| | EXPECT_THAT(AsVector(data->island_nv, nisland), ElementsAre(1, 2, 1)); |
| | EXPECT_THAT(AsVector(data->dof_island, nv), ElementsAre(0, 1, 1, 2)); |
| | EXPECT_THAT(AsVector(data->map_idof2dof, nv), ElementsAre(0, 1, 2, 3)); |
| | EXPECT_THAT(AsVector(data->map_dof2idof, nv), ElementsAre(0, 1, 2, 3)); |
| | EXPECT_THAT(AsVector(data->island_iefcadr, nisland), ElementsAre(0, 4, 8)); |
| | EXPECT_THAT(AsVector(data->island_nefc, nisland), ElementsAre(4, 4, 4)); |
| | EXPECT_THAT(AsVector(data->efc_island, nefc), |
| | ElementsAre(0, 0, 0, 0, 1, 1, 1, 1, 2, 2, 2, 2)); |
| | EXPECT_THAT(AsVector(data->map_iefc2efc, nefc), |
| | ElementsAre(0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11)); |
| |
|
| | mj_deleteData(data); |
| | mj_deleteModel(model); |
| | } |
| |
|
| | static const char* const kTendonWrapPath = |
| | "engine/testdata/island/tendon_wrap.xml"; |
| |
|
| | TEST_F(IslandTest, DenseSparse) { |
| | const std::string xml_path = GetTestDataFilePath(kTendonWrapPath); |
| | mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, nullptr, 0); |
| | mjData* data1 = mj_makeData(model); |
| | mjData* data2 = mj_makeData(model); |
| |
|
| | |
| | model->opt.jacobian = mjJAC_DENSE; |
| | while (!data1->nefc) { |
| | mj_step(model, data1); |
| | } |
| |
|
| | |
| | model->opt.jacobian = mjJAC_SPARSE; |
| | while (!data2->nefc) { |
| | mj_step(model, data2); |
| | } |
| |
|
| | |
| | int nv = model->nv; |
| | int nefc = data1->nefc; |
| | int nisland = data1->nisland; |
| |
|
| | |
| | EXPECT_EQ(data1->nidof, data2->nidof); |
| | EXPECT_EQ(data1->nefc, data2->nefc); |
| | EXPECT_EQ(data1->nisland, data2->nisland); |
| | EXPECT_EQ(data1->nefc, data2->nefc); |
| | EXPECT_EQ(AsVector(data1->island_idofadr, nisland), |
| | AsVector(data2->island_idofadr, nisland)); |
| | EXPECT_EQ(AsVector(data1->island_nv, nisland), |
| | AsVector(data2->island_nv, nisland)); |
| | EXPECT_EQ(AsVector(data1->dof_island, nv), |
| | AsVector(data2->dof_island, nv)); |
| | EXPECT_EQ(AsVector(data1->map_idof2dof, nv), |
| | AsVector(data2->map_idof2dof, nv)); |
| | EXPECT_EQ(AsVector(data1->map_dof2idof, nv), |
| | AsVector(data2->map_dof2idof, nv)); |
| | EXPECT_EQ(AsVector(data1->island_iefcadr, nisland), |
| | AsVector(data2->island_iefcadr, nisland)); |
| | EXPECT_EQ(AsVector(data1->island_nefc, nisland), |
| | AsVector(data2->island_nefc, nisland)); |
| | EXPECT_EQ(AsVector(data1->efc_island, nefc), |
| | AsVector(data2->efc_island, nefc)); |
| | EXPECT_EQ(AsVector(data1->map_iefc2efc, nefc), |
| | AsVector(data2->map_iefc2efc, nefc)); |
| | EXPECT_EQ(AsVector(data1->map_efc2iefc, nefc), |
| | AsVector(data2->map_efc2iefc, nefc)); |
| |
|
| | mj_deleteData(data2); |
| | mj_deleteData(data1); |
| | mj_deleteModel(model); |
| | } |
| |
|
| | static const char* const kIlslandEfcPath = |
| | "engine/testdata/island/island_efc.xml"; |
| |
|
| | TEST_F(IslandTest, IslandEfc) { |
| | const std::string xml_path = GetTestDataFilePath(kIlslandEfcPath); |
| | mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, nullptr, 0); |
| | mjData* data = mj_makeData(model); |
| |
|
| | while (data->time < 0.2) { |
| | mj_step(model, data); |
| | } |
| |
|
| | |
| | EXPECT_EQ(data->nisland, 4); |
| | EXPECT_EQ(data->ne, 7); |
| | EXPECT_EQ(data->nf, 2); |
| | EXPECT_EQ(data->nl, 1); |
| | EXPECT_EQ(data->nefc, 30); |
| |
|
| | mj_deleteData(data); |
| | mj_deleteModel(model); |
| | } |
| |
|
| | TEST_F(IslandTest, IslandFlex) { |
| | const std::string xml_path = GetTestDataFilePath("testdata/flex.xml"); |
| | mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, nullptr, 0); |
| | mjData* data1 = mj_makeData(model); |
| | mjData* data2 = mj_makeData(model); |
| |
|
| | model->opt.enableflags |= mjENBL_ISLAND; |
| | while (data1->time < 0.2) { |
| | mj_step(model, data1); |
| | } |
| |
|
| | model->opt.enableflags &= ~mjENBL_ISLAND; |
| | while (data2->time < 0.2) { |
| | mj_step(model, data2); |
| | } |
| |
|
| | EXPECT_THAT(AsVector(data1->qpos, model->nq), |
| | Pointwise(DoubleNear(1e-6), AsVector(data2->qpos, model->nq))); |
| |
|
| | mj_deleteData(data2); |
| | mj_deleteData(data1); |
| | mj_deleteModel(model); |
| | } |
| |
|
| | static const char* const k2H100Path = "engine/testdata/island/2humanoid100.xml"; |
| |
|
| | TEST_F(IslandTest, IslandJacobian) { |
| | for (const char* local_path : {kIlslandEfcPath, k2H100Path}) { |
| | const std::string xml_path = GetTestDataFilePath(local_path); |
| | mjModel* m = mj_loadXML(xml_path.c_str(), nullptr, nullptr, 0); |
| | int jac0 = m->opt.jacobian; |
| | mjData* d = mj_makeData(m); |
| |
|
| | for (mjtNum t_stop : {0.0, 0.2, 2.0}) { |
| | while (d->time < t_stop) { |
| | mj_step(m, d); |
| | } |
| |
|
| | for (mjtJacobian jac : {mjJAC_DENSE, mjJAC_SPARSE}) { |
| | m->opt.jacobian = jac; |
| | mj_forward(m, d); |
| |
|
| | int nv = m->nv; |
| | int nefc = d->nefc; |
| | int nisland = d->nisland; |
| | int nidof = d->nidof; |
| |
|
| | mjtNum* J = (mjtNum*)mju_malloc(sizeof(mjtNum) * nefc * nv); |
| | mjtNum* iJ = (mjtNum*)mju_malloc(sizeof(mjtNum) * nefc * nidof); |
| |
|
| | |
| | if (jac == mjJAC_DENSE) { |
| | mju_copy(J, d->efc_J, nefc * nv); |
| | mju_copy(iJ, d->iefc_J, nefc * nidof); |
| | } else { |
| | mju_sparse2dense(J, d->efc_J, nefc, nv, d->efc_J_rownnz, |
| | d->efc_J_rowadr, d->efc_J_colind); |
| | } |
| |
|
| | |
| | for (int island=0; island < nisland; island++) { |
| | int idof = d->island_idofadr[island]; |
| | int iefc = d->island_iefcadr[island]; |
| | int nefc_island = d->island_nefc[island]; |
| | int nv_island = d->island_nv[island]; |
| |
|
| | |
| |
|
| | |
| | mjtNum* J_island; |
| | if (jac == mjJAC_DENSE) { |
| | |
| | J_island = iJ + iefc * nidof; |
| | } else { |
| | |
| | mju_sparse2dense(iJ, d->iefc_J, nefc_island, nv_island, |
| | d->iefc_J_rownnz + iefc, |
| | d->iefc_J_rowadr + iefc, |
| | d->iefc_J_colind); |
| | J_island = iJ; |
| | } |
| |
|
| | |
| | for (int i=0; i < nefc_island; i++) { |
| | for (int j=0; j < nv_island; j++) { |
| | int efc = d->map_iefc2efc[iefc + i]; |
| | int dof = d->map_idof2dof[idof + j]; |
| | EXPECT_EQ(J_island[i * nv_island + j], J[efc * nv + dof]); |
| | } |
| | } |
| |
|
| | |
| |
|
| | |
| | if (jac == mjJAC_SPARSE) { |
| | |
| | mju_sparse2dense(iJ, d->iefc_JT, nv_island, nefc_island, |
| | d->iefc_JT_rownnz + idof, |
| | d->iefc_JT_rowadr + idof, |
| | d->iefc_JT_colind); |
| | J_island = iJ; |
| |
|
| | |
| | for (int i=0; i < nv_island; i++) { |
| | for (int j=0; j < nefc_island; j++) { |
| | int dof = d->map_idof2dof[idof + i]; |
| | int efc = d->map_iefc2efc[iefc + j]; |
| | EXPECT_EQ(J_island[i * nefc_island + j], J[efc * nv + dof]); |
| | } |
| | } |
| | } |
| | } |
| |
|
| | mju_free(iJ); |
| | mju_free(J); |
| | } |
| |
|
| | |
| | m->opt.jacobian = jac0; |
| | } |
| |
|
| | mj_deleteData(d); |
| | mj_deleteModel(m); |
| | } |
| | } |
| |
|
| | TEST_F(IslandTest, IslandInertia) { |
| | for (const char* local_path : {kIlslandEfcPath, k2H100Path}) { |
| | const std::string xml_path = GetTestDataFilePath(local_path); |
| | mjModel* m = mj_loadXML(xml_path.c_str(), nullptr, nullptr, 0); |
| | int nv = m->nv; |
| | mjData* d = mj_makeData(m); |
| | mjtNum* M = (mjtNum*)mju_malloc(sizeof(mjtNum) * nv * nv); |
| |
|
| | for (mjtNum t_stop : {0.0, 0.2, 2.0}) { |
| | while (d->time < t_stop) { |
| | mj_step(m, d); |
| | } |
| | mj_forward(m, d); |
| |
|
| | int nisland = d->nisland; |
| |
|
| | |
| | mj_fullM(m, M, d->qM); |
| |
|
| | |
| | for (int island=0; island < nisland; island++) { |
| | int nvi = d->island_nv[island]; |
| | mjtNum* Mi = (mjtNum*)mju_malloc(sizeof(mjtNum) * nvi * nvi); |
| |
|
| | int adr = d->island_idofadr[island]; |
| | mju_sparse2dense(Mi, d->iM, nvi, nvi, |
| | d->iM_rownnz + adr, |
| | d->iM_rowadr + adr, |
| | d->iM_colind); |
| |
|
| | |
| | for (int i=0; i < nvi; i++) { |
| | for (int j=0; j <= i; j++) { |
| | int dofi = d->map_idof2dof[adr + j]; |
| | int dofj = d->map_idof2dof[adr + i]; |
| | EXPECT_EQ(Mi[i * nvi + j], M[dofi * nv + dofj]); |
| | } |
| | } |
| | mju_free(Mi); |
| | } |
| | } |
| |
|
| | mju_free(M); |
| | mj_deleteData(d); |
| | mj_deleteModel(m); |
| | } |
| | } |
| |
|
| | TEST_F(IslandTest, IslandEfcElliptic) { |
| | const std::string xml_path = GetTestDataFilePath(kIlslandEfcPath); |
| | mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, nullptr, 0); |
| | mjData* data = mj_makeData(model); |
| |
|
| | model->opt.cone = mjCONE_ELLIPTIC; |
| | while (data->time < 0.2) { |
| | mj_step(model, data); |
| | } |
| | mj_forward(model, data); |
| |
|
| | EXPECT_EQ(data->nisland, 4); |
| | EXPECT_EQ(data->ne, 7); |
| | EXPECT_EQ(data->nf, 2); |
| | EXPECT_EQ(data->nl, 1); |
| | EXPECT_EQ(data->nefc, 25); |
| |
|
| | mj_deleteData(data); |
| | mj_deleteModel(model); |
| | } |
| |
|
| | } |
| | } |
| |
|