| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| |
|
| | |
| |
|
| | #include "src/engine/engine_inverse.h" |
| |
|
| | #include <string> |
| |
|
| | #include <gtest/gtest.h> |
| | #include <mujoco/mjmodel.h> |
| | #include <mujoco/mujoco.h> |
| | #include "test/fixture.h" |
| |
|
| | namespace mujoco { |
| | namespace { |
| |
|
| | using InverseTest = MujocoTest; |
| |
|
| | const int kSteps = 70; |
| | static const char* const kModelPath = "testdata/model.xml"; |
| |
|
| | |
| | TEST_F(InverseTest, ForwardInverseMatch) { |
| | const std::string xml_path = GetTestDataFilePath(kModelPath); |
| | mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, nullptr, 0); |
| | mjData* data = mj_makeData(model); |
| |
|
| | |
| | for (int i = 0; i < kSteps; ++i) { |
| | mj_step(model, data); |
| | } |
| | mj_forward(model, data); |
| |
|
| | |
| | mj_compareFwdInv(model, data); |
| |
|
| | |
| | mjtNum epsilon = 1e-10; |
| | EXPECT_LT(data->solver_fwdinv[0], epsilon); |
| | EXPECT_LT(data->solver_fwdinv[1], epsilon); |
| |
|
| | mj_deleteData(data); |
| | mj_deleteModel(model); |
| | } |
| |
|
| | |
| | TEST_F(InverseTest, DiscreteInverseMatch) { |
| | |
| | const std::string xml_path = GetTestDataFilePath(kModelPath); |
| | mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, nullptr, 0); |
| | int nv = model->nv; |
| | mjData* data = mj_makeData(model); |
| | int nstate = mj_stateSize(model, mjSTATE_INTEGRATION); |
| | mjtNum* state = (mjtNum*)mju_malloc(nstate * sizeof(mjtNum)); |
| | mjtNum* qvel_next = (mjtNum*)mju_malloc(nv * sizeof(mjtNum)); |
| | mjtNum* qacc_fd = (mjtNum*)mju_malloc(nv * sizeof(mjtNum)); |
| |
|
| | for (auto integrator : {mjINT_EULER, mjINT_IMPLICIT, mjINT_IMPLICITFAST}) { |
| | model->opt.integrator = integrator; |
| | for (bool invdiscrete : {false, true}) { |
| | |
| | mj_resetData(model, data); |
| | for (int i = 0; i < kSteps; ++i) { |
| | mj_step(model, data); |
| | } |
| |
|
| | |
| | mj_getState(model, data, state, mjSTATE_INTEGRATION); |
| |
|
| | |
| | mj_step(model, data); |
| | mju_copy(qvel_next, data->qvel, nv); |
| |
|
| | |
| | mj_setState(model, data, state, mjSTATE_INTEGRATION); |
| | mju_sub(qacc_fd, qvel_next, data->qvel, nv); |
| | mju_scl(qacc_fd, qacc_fd, 1/model->opt.timestep, nv); |
| |
|
| | |
| | mj_forward(model, data); |
| | mju_copy(data->qacc, qacc_fd, nv); |
| |
|
| | |
| | if (invdiscrete) { |
| | model->opt.enableflags |= mjENBL_INVDISCRETE; |
| | } else { |
| | model->opt.enableflags &= ~mjENBL_INVDISCRETE; |
| | } |
| |
|
| | |
| | mj_compareFwdInv(model, data); |
| |
|
| | |
| | if (invdiscrete) { |
| | mjtNum epsilon = 1e-9; |
| | EXPECT_LT(data->solver_fwdinv[0], epsilon); |
| | EXPECT_LT(data->solver_fwdinv[1], epsilon); |
| | } else { |
| | EXPECT_GT(data->solver_fwdinv[0], 1.0); |
| | EXPECT_GT(data->solver_fwdinv[1], 1.0); |
| | } |
| | } |
| | } |
| |
|
| | |
| | mju_free(qacc_fd); |
| | mju_free(qvel_next); |
| | mju_free(state); |
| | mj_deleteData(data); |
| | mj_deleteModel(model); |
| | } |
| |
|
| | } |
| | } |
| |
|