| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| |
|
| | |
| |
|
| | #include <random> |
| | #include <string> |
| | #include <vector> |
| |
|
| | #include <gmock/gmock.h> |
| | #include <gtest/gtest.h> |
| | #include <mujoco/mjmodel.h> |
| | #include <mujoco/mujoco.h> |
| | #include "src/engine/engine_core_smooth.h" |
| | #include "src/engine/engine_derivative.h" |
| | #include "src/engine/engine_derivative_fd.h" |
| | #include "src/engine/engine_forward.h" |
| | #include "src/engine/engine_io.h" |
| | #include "src/engine/engine_util_blas.h" |
| | #include "test/fixture.h" |
| |
|
| | namespace mujoco { |
| | namespace { |
| |
|
| | using ::std::vector; |
| | using ::testing::Pointwise; |
| | using ::testing::DoubleNear; |
| | using ::testing::Eq; |
| | using ::testing::Each; |
| | using ::testing::NotNull; |
| | using DerivativeTest = MujocoTest; |
| |
|
| | |
| | static const mjtNum absolute_tolerance = 1e-9; |
| |
|
| | |
| | static mjtNum RelativeError(mjtNum a, mjtNum b) { |
| | mjtNum nominator = mjMAX(0, mju_abs(a-b) - absolute_tolerance); |
| | mjtNum denominator = (mju_abs(a) + mju_abs(b) + absolute_tolerance); |
| | return nominator / denominator; |
| | } |
| |
|
| | |
| | |
| | static mjtNum CompareMatrices(mjtNum* Actual, mjtNum* Expected, |
| | int nrow, int ncol, mjtNum eps) { |
| | mjtNum max_error = 0; |
| | for (int i=0; i < nrow; i++) { |
| | for (int j=0; j < ncol; j++) { |
| | mjtNum actual = Actual[i*ncol+j]; |
| | mjtNum expected = Expected[i*ncol+j]; |
| | EXPECT_LT(RelativeError(actual, expected), eps) |
| | << "error at position (" << i << ", " << j << ")" |
| | << "\nexpected = " << expected |
| | << "\nactual = " << actual |
| | << "\ndiff = " << expected-actual; |
| | max_error = mjMAX(mju_abs(actual-expected), max_error); |
| | } |
| | } |
| | return max_error; |
| | } |
| |
|
| | static const char* const kEnergyConservingPendulumPath = |
| | "engine/testdata/derivative/energy_conserving_pendulum.xml"; |
| | static const char* const kTumblingThinObjectPath = |
| | "engine/testdata/derivative/tumbling_thin_object.xml"; |
| | static const char* const kTumblingThinObjectEllipsoidPath = |
| | "engine/testdata/derivative/tumbling_thin_object_ellipsoid.xml"; |
| | static const char* const kDampedActuatorsPath = |
| | "engine/testdata/derivative/damped_actuators.xml"; |
| | static const char* const kDamperActuatorsPath = |
| | "engine/testdata/actuation/damper.xml"; |
| | static const char* const kDampedPendulumPath = |
| | "engine/testdata/derivative/damped_pendulum.xml"; |
| | static const char* const kLinearPath = |
| | "engine/testdata/derivative/linear.xml"; |
| | static const char* const kModelPath = "testdata/model.xml"; |
| |
|
| | |
| | TEST_F(DerivativeTest, SmoothDvel) { |
| | |
| | for (const char* local_path : {kEnergyConservingPendulumPath, |
| | kTumblingThinObjectPath, |
| | kDampedActuatorsPath, |
| | kDamperActuatorsPath}) { |
| | const std::string xml_path = GetTestDataFilePath(local_path); |
| | mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, nullptr, 0); |
| | int nD = model->nD; |
| | mjData* data = mj_makeData(model); |
| |
|
| | for (mjtJacobian sparsity : {mjJAC_DENSE, mjJAC_SPARSE}) { |
| | |
| | model->opt.jacobian = sparsity; |
| |
|
| | |
| | mj_resetData(model, data); |
| | if (model->nu) { |
| | data->ctrl[0] = 0.1; |
| | } |
| | for (int i=0; i < 100; i++) { |
| | mj_step(model, data); |
| | } |
| | mj_forward(model, data); |
| |
|
| | |
| | mju_zero(data->qDeriv, nD); |
| | mjd_smooth_vel(model, data, true); |
| |
|
| | |
| | EXPECT_GT(mju_norm(data->qDeriv, nD), 0); |
| | vector<mjtNum> qDerivAnalytic = AsVector(data->qDeriv, nD); |
| |
|
| | |
| | mjtNum eps = 1e-7; |
| | mju_zero(data->qDeriv, nD); |
| | mjd_smooth_velFD(model, data, eps); |
| |
|
| | |
| | EXPECT_NE(mju_norm(data->qDeriv, nD), |
| | mju_norm(qDerivAnalytic.data(), nD)); |
| |
|
| | |
| | EXPECT_THAT(AsVector(data->qDeriv, nD), |
| | Pointwise(DoubleNear(eps), qDerivAnalytic)); |
| | } |
| | mj_deleteData(data); |
| | mj_deleteModel(model); |
| | } |
| | } |
| |
|
| | |
| | TEST_F(DerivativeTest, DisabledActuators) { |
| | |
| | static constexpr char xml1[] = R"( |
| | <mujoco> |
| | <option integrator="implicitfast"/> |
| | |
| | <worldbody> |
| | <body> |
| | <joint name="joint" type="slide"/> |
| | <geom size=".1"/> |
| | </body> |
| | </worldbody> |
| | |
| | <actuator> |
| | <position joint="joint" group="1" kp="2000" kv="200"/> |
| | </actuator> |
| | </mujoco> |
| | )"; |
| |
|
| | mjModel* m1 = LoadModelFromString(xml1); |
| | mjData* d1 = mj_makeData(m1); |
| |
|
| | d1->ctrl[0] = 6; |
| | while (d1->time < 1) |
| | mj_step(m1, d1); |
| |
|
| | |
| | static constexpr char xml2[] = R"( |
| | <mujoco> |
| | <option integrator="implicitfast" actuatorgroupdisable="2"/> |
| | |
| | <worldbody> |
| | <body> |
| | <joint name="joint" type="slide"/> |
| | <geom size=".1"/> |
| | </body> |
| | </worldbody> |
| | |
| | <actuator> |
| | <position joint="joint" group="1" kp="2000" kv="200"/> |
| | <intvelocity joint="joint" group="2" kp="2000" kv="200" actrange="-6 6"/> |
| | </actuator> |
| | </mujoco> |
| | )"; |
| |
|
| | mjModel* m2 = LoadModelFromString(xml2); |
| | mjData* d2 = mj_makeData(m2); |
| |
|
| | d2->ctrl[0] = 6; |
| | d2->ctrl[1] = 6; |
| |
|
| | while (d2->time < 1) |
| | mj_step(m2, d2); |
| |
|
| | |
| | EXPECT_EQ(d1->qvel[0], d2->qvel[0]); |
| |
|
| | mj_deleteData(d2); |
| | mj_deleteModel(m2); |
| | mj_deleteData(d1); |
| | mj_deleteModel(m1); |
| | } |
| |
|
| | |
| | TEST_F(DerivativeTest, ActuatorOrder) { |
| | |
| | static constexpr char xml1[] = R"( |
| | <mujoco> |
| | <option integrator="implicitfast"/> |
| | |
| | <worldbody> |
| | <body> |
| | <joint name="0" type="slide" range="-1 1"/> |
| | <geom size=".1"/> |
| | </body> |
| | <body pos="1 0 0"> |
| | <joint name="1" type="slide" range="-1 1"/> |
| | <geom size=".1"/> |
| | </body> |
| | </worldbody> |
| | |
| | <actuator> |
| | <muscle joint="0" ctrlrange="0 6"/> |
| | <damper joint="1" kv="200" ctrlrange="0 6"/> |
| | </actuator> |
| | </mujoco> |
| | )"; |
| |
|
| | char error[1024]; |
| | mjModel* m1 = LoadModelFromString(xml1, error, sizeof(error)); |
| | ASSERT_THAT(m1, NotNull()) << "Failed to load model: " << error; |
| | mjData* d1 = mj_makeData(m1); |
| |
|
| | d1->ctrl[0] = 6; |
| | d1->ctrl[1] = 6; |
| |
|
| | while (d1->time < 1) |
| | mj_step(m1, d1); |
| |
|
| | |
| | static constexpr char xml2[] = R"( |
| | <mujoco> |
| | <option integrator="implicitfast"/> |
| | |
| | <worldbody> |
| | <body> |
| | <joint name="0" type="slide" range="-1 1"/> |
| | <geom size=".1"/> |
| | </body> |
| | <body pos="1 0 0"> |
| | <joint name="1" type="slide" range="-1 1"/> |
| | <geom size=".1"/> |
| | </body> |
| | </worldbody> |
| | |
| | <actuator> |
| | <damper joint="1" kv="200" ctrlrange="0 6"/> |
| | <muscle joint="0" ctrlrange="0 6"/> |
| | </actuator> |
| | </mujoco> |
| | )"; |
| |
|
| | mjModel* m2 = LoadModelFromString(xml2, error, sizeof(error)); |
| | ASSERT_THAT(m2, NotNull()) << "Failed to load model: " << error; |
| | mjData* d2 = mj_makeData(m2); |
| |
|
| | d2->ctrl[0] = 6; |
| | d2->ctrl[1] = 6; |
| |
|
| | while (d2->time < 1) |
| | mj_step(m2, d2); |
| |
|
| | |
| | EXPECT_EQ(d1->qvel[0], d2->qvel[0]); |
| | EXPECT_EQ(d1->qvel[1], d2->qvel[1]); |
| |
|
| | mj_deleteData(d2); |
| | mj_deleteModel(m2); |
| | mj_deleteData(d1); |
| | mj_deleteModel(m1); |
| | } |
| |
|
| | |
| | TEST_F(DerivativeTest, PassiveDvel) { |
| | for (const char* local_path : {kTumblingThinObjectPath, |
| | kTumblingThinObjectEllipsoidPath}) { |
| | |
| | const std::string xml_path = GetTestDataFilePath(local_path); |
| | mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, nullptr, 0); |
| | int nD = model->nD; |
| | mjData* data = mj_makeData(model); |
| | |
| | mjtNum* qDerivAnalytic = (mjtNum*) mju_malloc(sizeof(mjtNum)*nD); |
| | mjtNum* qDerivFD = (mjtNum*) mju_malloc(sizeof(mjtNum)*nD); |
| |
|
| | for (mjtJacobian sparsity : {mjJAC_DENSE, mjJAC_SPARSE}) { |
| | |
| | model->opt.jacobian = sparsity; |
| |
|
| | |
| | mj_resetData(model, data); |
| | for (int i=0; i < 100; i++) { |
| | mj_step(model, data); |
| | } |
| | mj_forward(model, data); |
| |
|
| | |
| | mju_copy(qDerivAnalytic, data->qDeriv, nD); |
| |
|
| | |
| | mju_zero(data->qDeriv, nD); |
| | mju_zero(qDerivFD, nD); |
| | mjtNum eps = 1e-6; |
| | mjd_passive_velFD(model, data, eps); |
| |
|
| | |
| | mjtNum tol = 1e-4; |
| | EXPECT_THAT(AsVector(data->qDeriv, nD), |
| | Pointwise(DoubleNear(tol), AsVector(qDerivAnalytic, nD))); |
| | } |
| |
|
| | mju_free(qDerivFD); |
| | mju_free(qDerivAnalytic); |
| | mj_deleteData(data); |
| | mj_deleteModel(model); |
| | } |
| | } |
| |
|
| | |
| |
|
| | |
| | TEST_F(DerivativeTest, StepSkip) { |
| | const std::string xml_path = GetTestDataFilePath(kDampedPendulumPath); |
| | mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, nullptr, 0); |
| | mjData* data = mj_makeData(model); |
| | int nq = model->nq; |
| | int nv = model->nv; |
| |
|
| | |
| | model->opt.disableflags |= mjDSBL_WARMSTART; |
| |
|
| | for (const mjtIntegrator integrator : {mjINT_EULER, |
| | mjINT_IMPLICIT, |
| | mjINT_IMPLICITFAST}) { |
| | model->opt.integrator = integrator; |
| |
|
| | |
| | mj_resetData(model, data); |
| | for (int i=0; i < 20; i++) { |
| | mj_step(model, data); |
| | } |
| |
|
| | |
| | for (int j=0; j < model->njnt; j++) { |
| | if (model->jnt_type[j] == mjJNT_BALL) { |
| | int adr = model->jnt_qposadr[j]; |
| | for (int k=0; k < 4; k++) { |
| | data->qpos[adr + k] *= 8; |
| | } |
| | } |
| | } |
| |
|
| | |
| | vector<mjtNum> qpos = AsVector(data->qpos, nq); |
| | vector<mjtNum> qvel = AsVector(data->qvel, nv); |
| |
|
| | |
| | mj_step(model, data); |
| | vector<mjtNum> qpos_next = AsVector(data->qpos, nq); |
| | vector<mjtNum> qvel_next = AsVector(data->qvel, nv); |
| |
|
| | |
| | mju_copy(data->qpos, qpos.data(), nq); |
| | mju_copy(data->qvel, qvel.data(), nv); |
| | mj_step(model, data); |
| | EXPECT_THAT(AsVector(data->qpos, nq), Pointwise(Eq(), qpos_next)); |
| | EXPECT_THAT(AsVector(data->qvel, nv), Pointwise(Eq(), qvel_next)); |
| |
|
| | |
| | mju_copy(data->qpos, qpos.data(), nq); |
| | mju_copy(data->qvel, qvel.data(), nv); |
| | data->ctrl[0] = 1; |
| | mj_stepSkip(model, data, mjSTAGE_VEL, 0); |
| | vector<mjtNum> qpos_next_dctrl = AsVector(data->qpos, nq); |
| | vector<mjtNum> qvel_next_dctrl = AsVector(data->qvel, nv); |
| |
|
| | |
| | mju_copy(data->qpos, qpos.data(), nq); |
| | mju_copy(data->qvel, qvel.data(), nv); |
| | mj_step(model, data); |
| | EXPECT_THAT(AsVector(data->qpos, nq), Pointwise(Eq(), qpos_next_dctrl)); |
| | EXPECT_THAT(AsVector(data->qvel, nv), Pointwise(Eq(), qvel_next_dctrl)); |
| |
|
| | |
| | mju_copy(data->qpos, qpos.data(), nq); |
| | mju_copy(data->qvel, qvel.data(), nv); |
| | data->qvel[0] += 1; |
| | mj_stepSkip(model, data, mjSTAGE_POS, 0); |
| | vector<mjtNum> qpos_next_dvel = AsVector(data->qpos, nq); |
| | vector<mjtNum> qvel_next_dvel = AsVector(data->qvel, nv); |
| |
|
| | |
| | mju_copy(data->qpos, qpos.data(), nq); |
| | mju_copy(data->qvel, qvel.data(), nv); |
| | data->qvel[0] += 1; |
| | mj_step(model, data); |
| | EXPECT_THAT(AsVector(data->qpos, nq), Pointwise(Eq(), qpos_next_dvel)); |
| | EXPECT_THAT(AsVector(data->qvel, nv), Pointwise(Eq(), qvel_next_dvel)); |
| | } |
| |
|
| | mj_deleteData(data); |
| | mj_deleteModel(model); |
| | } |
| |
|
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | static void LinearSystem(const mjModel* m, mjData* d, mjtNum* A, mjtNum* B) { |
| | int nv = m->nv, nu = m->nu; |
| | mjtNum dt = m->opt.timestep; |
| | mj_markStack(d); |
| |
|
| | |
| | if (A) { |
| | mjtNum *Ac = mj_stackAllocNum(d, 2*nv*nv); |
| | |
| | mju_zero(Ac, 2*nv*nv); |
| | for (int i=0; i < nv; i++) { |
| | Ac[i*nv + i] = -m->jnt_stiffness[i]; |
| | Ac[nv*nv + i*nv + i] = -m->dof_damping[i]; |
| | } |
| | mj_solveLD(Ac, d->qH, d->qHDiagInv, nv, 2*nv, |
| | d->M_rownnz, d->M_rowadr, d->M_colind); |
| |
|
| | |
| | mju_transpose(A, Ac, 2*nv, nv); |
| | mju_scl(A, A, dt, nv*2*nv); |
| | mju_transpose(A+2*nv*nv, Ac, 2*nv, nv); |
| |
|
| | |
| | for (int i=0; i < nv; i++) { |
| | A[i*2*nv + nv + i] += 1; |
| | } |
| |
|
| | |
| | mju_scl(A, A, dt, 2*nv*2*nv); |
| |
|
| | |
| | for (int i=0; i < 2*nv; i++) { |
| | A[i*2*nv + i] += 1; |
| | } |
| | } |
| |
|
| | |
| | if (B) { |
| | mjtNum *Bc = mj_stackAllocNum(d, nu*nv); |
| | mjtNum *BcT = mj_stackAllocNum(d, nv*nu); |
| | mju_sparse2dense(Bc, d->actuator_moment, nu, nv, d->moment_rownnz, |
| | d->moment_rowadr, d->moment_colind); |
| | mj_solveLD(Bc, d->qH, d->qHDiagInv, nv, nu, |
| | d->M_rownnz, d->M_rowadr, d->M_colind); |
| | mju_transpose(BcT, Bc, nu, nv); |
| | mju_scl(B, BcT, dt*dt, nu*nv); |
| | mju_scl(B+nu*nv, BcT, dt, nu*nv); |
| | } |
| |
|
| | mj_freeStack(d); |
| | } |
| |
|
| | |
| | TEST_F(DerivativeTest, LinearSystem) { |
| | const std::string xml_path = GetTestDataFilePath(kLinearPath); |
| | mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, nullptr, 0); |
| | mjData* data = mj_makeData(model); |
| | int nv = model->nv, nu = model->nu; |
| |
|
| | |
| | data->ctrl[0] = .1; |
| | data->ctrl[1] = -.1; |
| | for (int i=0; i < 20; i++) { |
| | mj_step(model, data); |
| | } |
| |
|
| | |
| | mjtNum* A = (mjtNum*) mju_malloc(sizeof(mjtNum)*2*nv*2*nv); |
| | mjtNum* B = (mjtNum*) mju_malloc(sizeof(mjtNum)*2*nv*nu); |
| |
|
| | LinearSystem(model, data, A, B); |
| |
|
| | |
| | |
| | |
| |
|
| | |
| | mjtNum eps = 1e-6; |
| | mjtNum* AFD = (mjtNum*) mju_malloc(sizeof(mjtNum)*2*nv*2*nv); |
| | mjtNum* BFD = (mjtNum*) mju_malloc(sizeof(mjtNum)*2*nv*nu); |
| |
|
| | mjd_transitionFD(model, data, eps, 0, |
| | AFD, BFD, nullptr, nullptr); |
| |
|
| | |
| | |
| | |
| |
|
| | |
| | CompareMatrices(A, AFD, 2*nv, 2*nv, eps); |
| | CompareMatrices(B, BFD, 2*nv, nu, eps); |
| |
|
| | |
| | mjtNum* AFDc = (mjtNum*) mju_malloc(sizeof(mjtNum)*2*nv*2*nv); |
| | mjtNum* BFDc = (mjtNum*) mju_malloc(sizeof(mjtNum)*2*nv*nu); |
| | mjd_transitionFD(model, data, eps, 1, |
| | AFDc, BFDc, nullptr, nullptr); |
| |
|
| | |
| | CompareMatrices(AFD, AFDc, 2*nv, 2*nv, eps); |
| | CompareMatrices(BFD, BFDc, 2*nv, nu, eps); |
| |
|
| | mju_free(BFDc); |
| | mju_free(AFDc); |
| | mju_free(BFD); |
| | mju_free(AFD); |
| | mju_free(B); |
| | mju_free(A); |
| | mj_deleteData(data); |
| | mj_deleteModel(model); |
| | } |
| |
|
| | |
| | TEST_F(DerivativeTest, ClampedCtrlDerivatives) { |
| | const std::string xml_path = GetTestDataFilePath(kLinearPath); |
| | mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, nullptr, 0); |
| | mjData* data = mj_makeData(model); |
| | int nv = model->nv, nu = model->nu; |
| |
|
| | |
| | data->ctrl[0] = .1; |
| | data->ctrl[1] = -.1; |
| | for (int i=0; i < 20; i++) { |
| | mj_step(model, data); |
| | } |
| |
|
| | |
| | mjtNum* B = (mjtNum*) mju_malloc(sizeof(mjtNum)*2*nv*nu); |
| |
|
| | LinearSystem(model, data, nullptr, B); |
| |
|
| | |
| | mjtNum eps = 1e-6; |
| | mjtNum* BFD = (mjtNum*) mju_malloc(sizeof(mjtNum)*2*nv*nu); |
| |
|
| | |
| | data->ctrl[0] = 1; |
| | data->ctrl[1] = -1; |
| | mjd_transitionFD(model, data, eps, 0, |
| | nullptr, BFD, nullptr, nullptr); |
| | |
| | CompareMatrices(B, BFD, 2*nv, nu, eps); |
| |
|
| | |
| | mjd_transitionFD(model, data, eps, 1, |
| | nullptr, BFD, nullptr, nullptr); |
| | |
| | CompareMatrices(B, BFD, 2*nv, nu, eps); |
| |
|
| | |
| | data->ctrl[0] = 2; |
| | data->ctrl[1] = -2; |
| | mjd_transitionFD(model, data, eps, 0, |
| | nullptr, BFD, nullptr, nullptr); |
| | |
| | EXPECT_THAT(AsVector(BFD, 2*nv*nu), Each(Eq(0.0))); |
| |
|
| | |
| | EXPECT_EQ(data->ctrl[0], 2.0); |
| | EXPECT_EQ(data->ctrl[1], -2.0); |
| |
|
| | |
| | mjd_transitionFD(model, data, eps, 1, |
| | nullptr, BFD, nullptr, nullptr); |
| | |
| | EXPECT_THAT(AsVector(BFD, 2*nv*nu), Each(Eq(0.0))); |
| |
|
| | mju_free(BFD); |
| | mju_free(B); |
| | mj_deleteData(data); |
| | mj_deleteModel(model); |
| | } |
| |
|
| | |
| | TEST_F(DerivativeTest, SensorDerivatives) { |
| | static constexpr char xml[] = R"( |
| | <mujoco> |
| | <worldbody> |
| | <body> |
| | <joint name="joint" type="slide"/> |
| | <geom size=".1"/> |
| | </body> |
| | </worldbody> |
| | |
| | <actuator> |
| | <general name="actuator" joint="joint" gainprm="3"/> |
| | </actuator> |
| | |
| | <sensor> |
| | <jointpos joint="joint"/> |
| | <jointvel joint="joint"/> |
| | <actuatorfrc actuator="actuator"/> |
| | </sensor> |
| | </mujoco> |
| | )"; |
| |
|
| | mjModel* model = LoadModelFromString(xml); |
| | int nv = model->nv, nu = model->nu, ns = model->nsensordata; |
| | mjData* data = mj_makeData(model); |
| |
|
| | |
| | mjtNum eps = 1e-6; |
| | mjtNum* CFD = (mjtNum*) mju_malloc(sizeof(mjtNum)*ns*2*nv); |
| | mjtNum* DFD = (mjtNum*) mju_malloc(sizeof(mjtNum)*ns*nu); |
| | mjd_transitionFD(model, data, eps, 0, |
| | nullptr, nullptr, CFD, DFD); |
| |
|
| | |
| | mjtNum C[6] = { |
| | 1, 0, |
| | 0, 1, |
| | 0, 0 |
| | }; |
| |
|
| | mjtNum D[3] = { |
| | 0, |
| | 0, |
| | 3, |
| | }; |
| |
|
| | |
| | CompareMatrices(CFD, C, ns, 2*nv, eps); |
| | CompareMatrices(DFD, D, ns, nu, eps); |
| |
|
| | mju_free(DFD); |
| | mju_free(CFD); |
| | mj_deleteData(data); |
| | mj_deleteModel(model); |
| | } |
| |
|
| | |
| | TEST_F(DerivativeTest, SensorSkip) { |
| | static constexpr char xml[] = R"( |
| | <mujoco> |
| | <worldbody> |
| | <body> |
| | <joint name="joint" type="slide"/> |
| | <geom size=".1"/> |
| | </body> |
| | </worldbody> |
| | |
| | <actuator> |
| | <general name="actuator" joint="joint" gainprm="3"/> |
| | </actuator> |
| | |
| | <sensor> |
| | <jointpos joint="joint"/> |
| | </sensor> |
| | </mujoco> |
| | )"; |
| |
|
| | mjModel* model = LoadModelFromString(xml); |
| | int nv = model->nv, nu = model->nu; |
| | mjData* data = mj_makeData(model); |
| |
|
| | |
| | data->sensordata[0] = 1337; |
| |
|
| | |
| | mjtNum eps = 1e-6; |
| | mjtNum* BFD = (mjtNum*) mju_malloc(sizeof(mjtNum)*2*nv*nu); |
| | mjd_transitionFD(model, data, eps, 0, |
| | nullptr, BFD, nullptr, nullptr); |
| |
|
| | EXPECT_EQ(data->sensordata[0], 1337) << "sensors should not be recomputed"; |
| |
|
| | mju_free(BFD); |
| | mj_deleteData(data); |
| | mj_deleteModel(model); |
| | } |
| |
|
| | |
| | TEST_F(DerivativeTest, NoStateMutation) { |
| | const std::string xml_path = GetTestDataFilePath(kModelPath); |
| | mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, nullptr, 0); |
| | ASSERT_THAT(model, NotNull()); |
| | mjData* data0 = mj_makeData(model); |
| | mjData* data = mj_makeData(model); |
| | int nv = model->nv, nu = model->nu, na = model->na, ns = model->nsensordata; |
| |
|
| | |
| | data->time = data0->time = 0.5; |
| |
|
| | for (int i=0; i < nv; i++) { |
| | data->qpos[i] = data0->qpos[i] = (mjtNum) i+1; |
| | data->qvel[i] = data0->qvel[i] = (mjtNum) i+2; |
| | } |
| |
|
| | |
| | for (int i=0; i < nu; i++) { |
| | data->ctrl[i] = data0->ctrl[i] = (mjtNum) i+1; |
| | } |
| |
|
| | |
| | for (int i=0; i < na; i++) { |
| | data->act[i] = data0->act[i] = (mjtNum) i+1; |
| | } |
| |
|
| |
|
| | |
| | int ndx = nv+nv+na; |
| | mjtNum* A = (mjtNum*) mju_malloc(sizeof(mjtNum)*ndx*ndx); |
| | mjtNum* B = (mjtNum*) mju_malloc(sizeof(mjtNum)*ndx*nu); |
| | mjtNum* C = (mjtNum*) mju_malloc(sizeof(mjtNum)*ns*ndx); |
| | mjtNum* D = (mjtNum*) mju_malloc(sizeof(mjtNum)*ns*nu); |
| | mjtNum eps = 1e-6; |
| | mjd_transitionFD(model, data, eps, 0, A, B, C, D); |
| |
|
| | |
| | EXPECT_EQ(data->time, data0->time); |
| | EXPECT_EQ(AsVector(data->qpos, model->nq), AsVector(data0->qpos, model->nq)); |
| | EXPECT_EQ(AsVector(data->qvel, nv), AsVector(data0->qvel, nv)); |
| | EXPECT_EQ(AsVector(data->act, na), AsVector(data0->act, na)); |
| | EXPECT_EQ(AsVector(data->ctrl, nu), AsVector(data0->ctrl, nu)); |
| |
|
| | mju_free(D); |
| | mju_free(C); |
| | mju_free(B); |
| | mju_free(A); |
| | mj_deleteData(data); |
| | mj_deleteData(data0); |
| | mj_deleteModel(model); |
| | } |
| |
|
| | |
| | TEST_F(DerivativeTest, DenseSparseRneEquivalent) { |
| | |
| | for (const char* local_path : {kEnergyConservingPendulumPath, |
| | kTumblingThinObjectPath, |
| | kDampedActuatorsPath, |
| | kDamperActuatorsPath}) { |
| | const std::string xml_path = GetTestDataFilePath(local_path); |
| | mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, nullptr, 0); |
| | int nD = model->nD; |
| | mjtNum* qDeriv = (mjtNum*) mju_malloc(sizeof(mjtNum)*nD); |
| | mjData* data = mj_makeData(model); |
| |
|
| | |
| | mj_resetData(model, data); |
| | if (model->nu) { |
| | data->ctrl[0] = 0.1; |
| | } |
| | for (int i=0; i < 100; i++) { |
| | mj_step(model, data); |
| | } |
| | mj_forward(model, data); |
| |
|
| | |
| | mjd_smooth_vel(model, data, 1); |
| | mju_copy(qDeriv, data->qDeriv, nD); |
| |
|
| | |
| | mju_zero(data->qDeriv, model->nD); |
| | mjd_actuator_vel(model, data); |
| | mjd_passive_vel(model, data); |
| | mjd_rne_vel_dense(model, data); |
| |
|
| | |
| | mjtNum eps = 1e-12; |
| | EXPECT_THAT(AsVector(data->qDeriv, nD), |
| | Pointwise(DoubleNear(eps), AsVector(qDeriv, nD))); |
| |
|
| | mj_deleteData(data); |
| | mju_free(qDeriv); |
| | mj_deleteModel(model); |
| | } |
| | } |
| |
|
| | |
| | TEST_F(DerivativeTest, LinearSystemInverse) { |
| | const std::string xml_path = GetTestDataFilePath(kLinearPath); |
| | mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, nullptr, 0); |
| | mjData* data = mj_makeData(model); |
| |
|
| | int nv = model->nv; |
| | int ns = model->nsensordata; |
| | int nM = model->nM; |
| |
|
| | vector<mjtNum> DfDq(nv*nv); |
| | vector<mjtNum> DfDv(nv*nv); |
| | vector<mjtNum> DfDa(nv*nv); |
| | vector<mjtNum> DsDq(nv*ns); |
| | vector<mjtNum> DsDv(nv*ns); |
| | vector<mjtNum> DsDa(nv*ns); |
| | vector<mjtNum> DmDq(nv*nM); |
| |
|
| | |
| | mj_forward(model, data); |
| |
|
| | |
| | mjtNum eps = 1e-6; |
| | mjtByte flg_actuation = 0; |
| | mjd_inverseFD(model, data, eps, flg_actuation, |
| | DfDq.data(), DfDv.data(), DfDa.data(), |
| | DsDq.data(), DsDv.data(), DsDa.data(), |
| | DmDq.data()); |
| |
|
| | |
| | vector<mjtNum> DfDq_expect = {model->jnt_stiffness[0], 0, 0, |
| | 0, model->jnt_stiffness[1], 0, |
| | 0, 0, model->jnt_stiffness[2]}; |
| | EXPECT_THAT(DfDq, Pointwise(DoubleNear(eps), DfDq_expect)); |
| |
|
| | |
| | vector<mjtNum> DfDv_expect = {model->dof_damping[0], 0, 0, |
| | 0, model->dof_damping[1], 0, |
| | 0, 0, model->dof_damping[2]}; |
| | EXPECT_THAT(DfDv, Pointwise(DoubleNear(eps), DfDv_expect)); |
| |
|
| | |
| | vector<mjtNum> DfDa_expect(nv*nv, 0); |
| | mj_fullM(model, DfDa_expect.data(), data->qM); |
| | EXPECT_THAT(DfDa, Pointwise(DoubleNear(eps), DfDa_expect)); |
| |
|
| | |
| | vector<mjtNum> DsDq_expect(nv*ns, 0); |
| | int dof_index = 0; |
| | int sensordata_index = model->sensor_adr[1]; |
| | DsDq_expect[dof_index*ns + sensordata_index] = 1; |
| | EXPECT_THAT(DsDq, Pointwise(DoubleNear(eps), DsDq_expect)); |
| |
|
| | |
| | vector<mjtNum> DsDv_expect(nv*ns, 0); |
| | dof_index = 1; |
| | sensordata_index = model->sensor_adr[0]; |
| | DsDv_expect[dof_index*ns + sensordata_index] = 1; |
| | EXPECT_THAT(DsDv, Pointwise(DoubleNear(eps), DsDv_expect)); |
| |
|
| | |
| | |
| | vector<mjtNum> DsDa_expect(nv*ns, 0); |
| | dof_index = 0; |
| | sensordata_index = model->sensor_adr[2] + 1; |
| | DsDa_expect[dof_index*ns + sensordata_index] = 1; |
| | dof_index = 1; |
| | DsDa_expect[dof_index*ns + sensordata_index] = 1; |
| | EXPECT_THAT(DsDa, Pointwise(DoubleNear(eps), DsDa_expect)); |
| |
|
| | |
| | vector<mjtNum> DmDq_expect(nv*nM, 0); |
| | EXPECT_THAT(DmDq, Pointwise(DoubleNear(eps), DmDq_expect)); |
| |
|
| | mj_deleteData(data); |
| | mj_deleteModel(model); |
| | } |
| |
|
| | |
| | void randomQuatPair(mjtNum qa[4], mjtNum qb[4], mjtNum angle, int seed) { |
| | |
| | std::mt19937_64 rng; |
| | rng.seed(seed); |
| | std::normal_distribution<double> dist(0, 1); |
| |
|
| | |
| | for (int i=0; i < 4; i++) { |
| | qa[i] = qb[i] = dist(rng); |
| | } |
| | mju_normalize4(qa); |
| | mju_normalize4(qb); |
| |
|
| | |
| | mjtNum dir[3]; |
| | for (int i=0; i < 3; i++) { |
| | dir[i] = dist(rng); |
| | } |
| | mju_normalize3(dir); |
| | mju_quatIntegrate(qb, dir, angle); |
| | } |
| |
|
| | |
| | static void subQuatFD(mjtNum Da[9], mjtNum Db[9], |
| | const mjtNum qa[4], const mjtNum qb[4], mjtNum eps) { |
| | |
| | mjtNum y[3]; |
| | mju_subQuat(y, qa, qb); |
| |
|
| | mjtNum dq[3]; |
| | mjtNum dqa[4]; |
| | mjtNum dqb[4]; |
| | mjtNum dy[3]; |
| | mjtNum DaT[9]; |
| | mjtNum DbT[9]; |
| |
|
| | for (int i = 0; i < 3; i++) { |
| | |
| | mju_zero3(dq); |
| | dq[i] = 1.0; |
| |
|
| | |
| | mju_copy4(dqa, qa); |
| | mju_quatIntegrate(dqa, dq, eps); |
| | mju_subQuat(dy, dqa, qb); |
| |
|
| | mju_sub3(DaT + i * 3, dy, y); |
| | mju_scl3(DaT + i * 3, DaT + i * 3, 1.0 / eps); |
| |
|
| | |
| | mju_copy4(dqb, qb); |
| | mju_quatIntegrate(dqb, dq, eps); |
| | mju_subQuat(dy, qa, dqb); |
| |
|
| | mju_sub3(DbT + i * 3, dy, y); |
| | mju_scl3(DbT + i * 3, DbT + i * 3, 1.0 / eps); |
| | } |
| |
|
| | |
| | mju_transpose(Da, DaT, 3, 3); |
| | mju_transpose(Db, DbT, 3, 3); |
| | } |
| |
|
| | TEST_F(DerivativeTest, SubQuat) { |
| | const int nrepeats = 10; |
| | const mjtNum eps = 1e-7; |
| |
|
| | int seed = 1; |
| | for (int i = 0; i < nrepeats; i++) { |
| | for (mjtNum angle : {0.0, 1e-9, 1e-5, 1e-2, 1.0, 4.0}) { |
| | |
| | mjtNum qa[4]; |
| | mjtNum qb[4]; |
| |
|
| | |
| | randomQuatPair(qa, qb, angle, seed++); |
| |
|
| | |
| | mjtNum Da[9]; |
| | mjtNum Db[9]; |
| | mjd_subQuat(qa, qb, Da, Db); |
| |
|
| | |
| | mjtNum DaFD[9]; |
| | mjtNum DbFD[9]; |
| | subQuatFD(DaFD, DbFD, qa, qb, eps); |
| |
|
| | |
| | EXPECT_THAT(AsVector(DaFD, 9), |
| | Pointwise(DoubleNear(eps), AsVector(Da, 9))); |
| | EXPECT_THAT(AsVector(DbFD, 9), |
| | Pointwise(DoubleNear(eps), AsVector(Db, 9))); |
| | } |
| | } |
| | } |
| |
|
| | |
| | static void randomQuatVel(mjtNum quat[4], mjtNum vel[3], int seed) { |
| | |
| | std::mt19937_64 rng; |
| | rng.seed(seed); |
| | std::normal_distribution<double> dist(0, 1); |
| |
|
| | |
| | for (int i=0; i < 4; i++) { |
| | quat[i] = dist(rng); |
| | } |
| | mju_normalize4(quat); |
| |
|
| | |
| | for (int i=0; i < 3; i++) { |
| | vel[i] = dist(rng); |
| | } |
| | } |
| |
|
| | |
| | void mjd_quatIntegrateFD(mjtNum Dquat[9], mjtNum Ds[9], |
| | mjtNum Dvel[9], mjtNum Dh[3], |
| | const mjtNum quat[4], const mjtNum vel[3], |
| | mjtNum h, mjtNum eps) { |
| | |
| | mjtNum y[4] = {quat[0], quat[1], quat[2], quat[3]}; |
| | mju_quatIntegrate(y, vel, h); |
| |
|
| | mjtNum dx[3]; |
| | mjtNum dq[4]; |
| | mjtNum dy[3]; |
| | mjtNum DquatT[9]; |
| | mjtNum DsT[9]; |
| | mjtNum DvelT[9]; |
| |
|
| | for (int i = 0; i < 3; i++) { |
| | |
| | mju_zero3(dx); |
| | dx[i] = 1.0; |
| |
|
| | |
| | mju_copy4(dq, quat); |
| | mju_quatIntegrate(dq, dx, eps); |
| | mju_quatIntegrate(dq, vel, h); |
| | mju_subQuat(dy, dq, y); |
| | mju_scl3(DquatT + i * 3, dy, 1.0 / eps); |
| |
|
| | |
| | mju_copy4(dq, quat); |
| | mjtNum dsv[3] = {vel[0]*h, vel[1]*h, vel[2]*h}; |
| | mju_addToScl3(dsv, dx, eps); |
| | mju_quatIntegrate(dq, dsv, 1.0); |
| | mju_subQuat(dy, dq, y); |
| | mju_scl3(DsT + i * 3, dy, 1.0 / eps); |
| |
|
| | |
| | mju_copy4(dq, quat); |
| | mjtNum dv[3] = {vel[0], vel[1], vel[2]}; |
| | mju_addToScl3(dv, dx, eps); |
| | mju_quatIntegrate(dq, dv, h); |
| | mju_subQuat(dy, dq, y); |
| | mju_scl3(DvelT + i * 3, dy, 1.0 / eps); |
| | } |
| |
|
| | |
| | mju_copy4(dq, quat); |
| | mju_quatIntegrate(dq, vel, h + eps); |
| | mju_subQuat(dy, dq, y); |
| | mju_scl3(Dh, dy, 1.0 / eps); |
| |
|
| | |
| | mju_transpose(Dquat, DquatT, 3, 3); |
| | mju_transpose(Ds, DsT, 3, 3); |
| | mju_transpose(Dvel, DsT, 3, 3); |
| | } |
| |
|
| | TEST_F(DerivativeTest, quatIntegrate) { |
| | const int nrepeats = 10; |
| | const mjtNum eps = 1e-7; |
| |
|
| | int seed = 1; |
| | for (int i = 0; i < nrepeats; i++) { |
| | for (mjtNum h : {0.0, 1e-9, 1e-5, 1e-2, 1.0, 4.0}) { |
| | |
| | mjtNum quat[4]; |
| | mjtNum vel[3]; |
| | randomQuatVel(quat, vel, seed++); |
| |
|
| | |
| | mjtNum Dquat[9]; |
| | mjtNum Dvel[9]; |
| | mjtNum Dh[3]; |
| | mjd_quatIntegrate(vel, h, Dquat, Dvel, Dh); |
| |
|
| | |
| | mjtNum DquatFD[9]; |
| | mjtNum DsFD[9]; |
| | mjtNum DvelFD[9]; |
| | mjtNum DhFD[3]; |
| | mjd_quatIntegrateFD(DquatFD, DsFD, DvelFD, DhFD, quat, vel, h, eps); |
| |
|
| | |
| | EXPECT_THAT(AsVector(DvelFD, 9), Pointwise(DoubleNear(eps), DsFD)); |
| |
|
| | |
| | EXPECT_THAT(AsVector(DquatFD, 9), Pointwise(DoubleNear(eps), Dquat)); |
| | EXPECT_THAT(AsVector(DvelFD, 9), Pointwise(DoubleNear(eps), Dvel)); |
| | EXPECT_THAT(AsVector(DhFD, 3), Pointwise(DoubleNear(eps), Dh)); |
| | } |
| | } |
| | } |
| |
|
| | } |
| | } |
| |
|