| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| |
|
| | #include "engine/engine_inverse.h" |
| |
|
| | #include <stddef.h> |
| |
|
| | #include <mujoco/mjdata.h> |
| | #include <mujoco/mjmacro.h> |
| | #include <mujoco/mjmodel.h> |
| | #include <mujoco/mjsan.h> |
| | #include "engine/engine_collision_driver.h" |
| | #include "engine/engine_core_constraint.h" |
| | #include "engine/engine_core_smooth.h" |
| | #include "engine/engine_derivative.h" |
| | #include "engine/engine_io.h" |
| | #include "engine/engine_macro.h" |
| | #include "engine/engine_forward.h" |
| | #include "engine/engine_sensor.h" |
| | #include "engine/engine_support.h" |
| | #include "engine/engine_util_blas.h" |
| | #include "engine/engine_util_errmem.h" |
| | #include "engine/engine_util_misc.h" |
| | #include "engine/engine_util_sparse.h" |
| |
|
| | |
| | void mj_invPosition(const mjModel* m, mjData* d) { |
| | TM_START1; |
| | TM_START; |
| |
|
| | mj_kinematics(m, d); |
| | mj_comPos(m, d); |
| | mj_camlight(m, d); |
| | mj_flex(m, d); |
| | mj_tendon(m, d); |
| | TM_END(mjTIMER_POS_KINEMATICS); |
| |
|
| | mj_makeM(m, d); |
| | mj_factorM(m, d); |
| |
|
| | mj_collision(m, d); |
| |
|
| | TM_RESTART; |
| | mj_makeConstraint(m, d); |
| | TM_END(mjTIMER_POS_MAKE); |
| |
|
| | TM_RESTART; |
| | mj_transmission(m, d); |
| | TM_ADD(mjTIMER_POS_KINEMATICS); |
| |
|
| | TM_END1(mjTIMER_POSITION); |
| | } |
| |
|
| |
|
| |
|
| | |
| | void mj_invVelocity(const mjModel* m, mjData* d) { |
| | mj_fwdVelocity(m, d); |
| | } |
| |
|
| |
|
| |
|
| | |
| | static void mj_discreteAcc(const mjModel* m, mjData* d) { |
| | int nv = m->nv, nM = m->nM, nD = m->nD, dof_damping; |
| | mjtNum *qacc = d->qacc; |
| |
|
| | mj_markStack(d); |
| | mjtNum* qfrc = mjSTACKALLOC(d, nv, mjtNum); |
| |
|
| | |
| | switch ((mjtIntegrator) m->opt.integrator) { |
| | case mjINT_RK4: |
| | |
| | mjERROR("discrete inverse dynamics is not supported by RK4 integrator"); |
| | return; |
| |
|
| | case mjINT_EULER: |
| | |
| | dof_damping = 0; |
| | if (!mjDISABLED(mjDSBL_EULERDAMP)) { |
| | for (int i=0; i < nv; i++) { |
| | if (m->dof_damping[i] > 0) { |
| | dof_damping = 1; |
| | break; |
| | } |
| | } |
| | } |
| |
|
| | |
| | if (!dof_damping) { |
| | mj_freeStack(d); |
| | return; |
| | } |
| |
|
| | |
| | mj_mulM(m, d, qfrc, qacc); |
| | for (int i=0; i < nv; i++) { |
| | qfrc[i] += m->opt.timestep * m->dof_damping[i] * d->qacc[i]; |
| | } |
| | break; |
| |
|
| | case mjINT_IMPLICIT: |
| | |
| | mjd_smooth_vel(m, d, 1); |
| |
|
| | |
| | mju_gather(d->qLU, d->qM, d->mapM2D, nD); |
| |
|
| | |
| | mju_addToScl(d->qLU, d->qDeriv, -m->opt.timestep, m->nD); |
| |
|
| | |
| | mju_mulMatVecSparse(qfrc, d->qLU, qacc, nv, |
| | d->D_rownnz, d->D_rowadr, d->D_colind, NULL); |
| | break; |
| |
|
| | case mjINT_IMPLICITFAST: |
| | |
| | mjd_smooth_vel(m, d, 0); |
| |
|
| | |
| | mjtNum* qMsave = mjSTACKALLOC(d, m->nM, mjtNum); |
| | mju_copy(qMsave, d->qM, m->nM); |
| |
|
| | |
| | mjtNum* qDerivReduced = mjSTACKALLOC(d, m->nM, mjtNum); |
| | for (int i=0; i < nM; i++) { |
| | qDerivReduced[i] = d->qDeriv[d->mapD2M[i]]; |
| | } |
| | mju_addToScl(d->qM, qDerivReduced, -m->opt.timestep, m->nM); |
| |
|
| | |
| | mj_mulM(m, d, qfrc, qacc); |
| |
|
| | |
| | mju_copy(d->qM, qMsave, m->nM); |
| | break; |
| | } |
| |
|
| | |
| | mj_solveM(m, d, qacc, qfrc, 1); |
| |
|
| | mj_freeStack(d); |
| | } |
| |
|
| |
|
| |
|
| | |
| | void mj_invConstraint(const mjModel* m, mjData* d) { |
| | TM_START; |
| | int nefc = d->nefc; |
| |
|
| | |
| | if (!nefc) { |
| | mju_zero(d->qfrc_constraint, m->nv); |
| | TM_END(mjTIMER_CONSTRAINT); |
| | return; |
| | } |
| |
|
| | mj_markStack(d); |
| | mjtNum* jar = mjSTACKALLOC(d, nefc, mjtNum); |
| |
|
| | |
| | mj_mulJacVec(m, d, jar, d->qacc); |
| | mju_subFrom(jar, d->efc_aref, nefc); |
| |
|
| | |
| | mj_constraintUpdate(m, d, jar, NULL, 0); |
| |
|
| | mj_freeStack(d); |
| | TM_END(mjTIMER_CONSTRAINT); |
| | } |
| |
|
| |
|
| |
|
| | |
| | void mj_inverseSkip(const mjModel* m, mjData* d, |
| | int skipstage, int skipsensor) { |
| | TM_START; |
| | mj_markStack(d); |
| | mjtNum* qacc; |
| | int nv = m->nv; |
| |
|
| | |
| | if (skipstage < mjSTAGE_POS) { |
| | mj_invPosition(m, d); |
| | if (!skipsensor) { |
| | mj_sensorPos(m, d); |
| | } |
| | if (mjENABLED(mjENBL_ENERGY)) { |
| | mj_energyPos(m, d); |
| | } |
| | } |
| |
|
| | |
| | if (skipstage < mjSTAGE_VEL) { |
| | mj_invVelocity(m, d); |
| | if (!skipsensor) { |
| | mj_sensorVel(m, d); |
| | } |
| | if (mjENABLED(mjENBL_ENERGY)) { |
| | mj_energyVel(m, d); |
| | } |
| | } |
| |
|
| | if (mjENABLED(mjENBL_INVDISCRETE)) { |
| | |
| | qacc = mjSTACKALLOC(d, nv, mjtNum); |
| | mju_copy(qacc, d->qacc, nv); |
| |
|
| | |
| | mj_discreteAcc(m, d); |
| | } |
| |
|
| | |
| | mj_invConstraint(m, d); |
| |
|
| | |
| | mj_rne(m, d, 0, d->qfrc_inverse); |
| | mj_tendonBias(m, d, d->qfrc_inverse); |
| |
|
| | if (!skipsensor) { |
| | mj_sensorAcc(m, d); |
| | } |
| |
|
| | |
| | mjtNum* Ma = mjSTACKALLOC(d, nv, mjtNum); |
| | mj_mulM(m, d, Ma, d->qacc); |
| |
|
| | |
| | for (int i=0; i < nv; i++) { |
| | d->qfrc_inverse[i] += Ma[i] - d->qfrc_passive[i] - d->qfrc_constraint[i]; |
| | } |
| |
|
| | if (mjENABLED(mjENBL_INVDISCRETE)) { |
| | |
| | mju_copy(d->qacc, qacc, nv); |
| | } |
| |
|
| | mj_freeStack(d); |
| | TM_END(mjTIMER_INVERSE); |
| | } |
| |
|
| |
|
| |
|
| | |
| | void mj_inverse(const mjModel* m, mjData* d) { |
| | mj_inverseSkip(m, d, mjSTAGE_NONE, 0); |
| | } |
| |
|
| |
|
| |
|
| | |
| | |
| | |
| | void mj_compareFwdInv(const mjModel* m, mjData* d) { |
| | int nv = m->nv, nefc = d->nefc; |
| | mjtNum *qforce, *dif, *save_qfrc_constraint, *save_efc_force; |
| |
|
| | |
| | d->solver_fwdinv[0] = d->solver_fwdinv[1] = 0; |
| | if (!nefc) { |
| | return; |
| | } |
| |
|
| | |
| | mj_markStack(d); |
| | qforce = mjSTACKALLOC(d, nv, mjtNum); |
| | dif = mjSTACKALLOC(d, nv, mjtNum); |
| | save_qfrc_constraint = mjSTACKALLOC(d, nv, mjtNum); |
| | save_efc_force = mjSTACKALLOC(d, nefc, mjtNum); |
| |
|
| | |
| | |
| | mju_add(qforce, d->qfrc_applied, d->qfrc_actuator, nv); |
| | mj_xfrcAccumulate(m, d, qforce); |
| |
|
| | |
| | mju_copy(save_qfrc_constraint, d->qfrc_constraint, nv); |
| | mju_copy(save_efc_force, d->efc_force, nefc); |
| |
|
| | |
| | mj_inverseSkip(m, d, mjSTAGE_VEL, 1); |
| |
|
| | |
| | mju_sub(dif, save_qfrc_constraint, d->qfrc_constraint, nv); |
| | d->solver_fwdinv[0] = mju_norm(dif, nv); |
| | mju_sub(dif, qforce, d->qfrc_inverse, nv); |
| | d->solver_fwdinv[1] = mju_norm(dif, nv); |
| |
|
| | |
| | mju_copy(d->qfrc_constraint, save_qfrc_constraint, nv); |
| | mju_copy(d->efc_force, save_efc_force, nefc); |
| |
|
| | mj_freeStack(d); |
| | } |
| |
|