| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| |
|
| | #include "engine/engine_forward.h" |
| |
|
| | #include <stddef.h> |
| | #include <stdio.h> |
| |
|
| | #include <mujoco/mjdata.h> |
| | #include <mujoco/mjmacro.h> |
| | #include <mujoco/mjmodel.h> |
| | #include <mujoco/mjsan.h> |
| | #include <mujoco/mjplugin.h> |
| | #include "engine/engine_callback.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_inverse.h" |
| | #include "engine/engine_island.h" |
| | #include "engine/engine_io.h" |
| | #include "engine/engine_macro.h" |
| | #include "engine/engine_passive.h" |
| | #include "engine/engine_plugin.h" |
| | #include "engine/engine_sensor.h" |
| | #include "engine/engine_solver.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_solve.h" |
| | #include "engine/engine_util_sparse.h" |
| | #include "thread/thread_pool.h" |
| | #include "thread/thread_task.h" |
| |
|
| |
|
| |
|
| | |
| |
|
| | |
| | void mj_checkPos(const mjModel* m, mjData* d) { |
| | for (int i=0; i < m->nq; i++) { |
| | if (mju_isBad(d->qpos[i])) { |
| | mj_warning(d, mjWARN_BADQPOS, i); |
| | if (!mjDISABLED(mjDSBL_AUTORESET)) { |
| | mj_resetData(m, d); |
| | } |
| | d->warning[mjWARN_BADQPOS].number++; |
| | d->warning[mjWARN_BADQPOS].lastinfo = i; |
| | return; |
| | } |
| | } |
| | } |
| |
|
| |
|
| |
|
| | |
| | void mj_checkVel(const mjModel* m, mjData* d) { |
| | for (int i=0; i < m->nv; i++) { |
| | if (mju_isBad(d->qvel[i])) { |
| | mj_warning(d, mjWARN_BADQVEL, i); |
| | if (!mjDISABLED(mjDSBL_AUTORESET)) { |
| | mj_resetData(m, d); |
| | } |
| | d->warning[mjWARN_BADQVEL].number++; |
| | d->warning[mjWARN_BADQVEL].lastinfo = i; |
| | return; |
| | } |
| | } |
| | } |
| |
|
| |
|
| |
|
| | |
| | void mj_checkAcc(const mjModel* m, mjData* d) { |
| | for (int i=0; i < m->nv; i++) { |
| | if (mju_isBad(d->qacc[i])) { |
| | mj_warning(d, mjWARN_BADQACC, i); |
| | if (!mjDISABLED(mjDSBL_AUTORESET)) { |
| | mj_resetData(m, d); |
| | } |
| | d->warning[mjWARN_BADQACC].number++; |
| | d->warning[mjWARN_BADQACC].lastinfo = i; |
| | if (!mjDISABLED(mjDSBL_AUTORESET)) { |
| | mj_forward(m, d); |
| | } |
| | return; |
| | } |
| | } |
| | } |
| |
|
| |
|
| |
|
| | |
| |
|
| | |
| | struct mjFwdPositionArgs_ { |
| | const mjModel* m; |
| | mjData* d; |
| | }; |
| | typedef struct mjFwdPositionArgs_ mjFwdPositionArgs; |
| |
|
| | |
| | void* mj_inertialThreaded(void* args) { |
| | mjFwdPositionArgs* forward_args = (mjFwdPositionArgs*) args; |
| | mj_makeM(forward_args->m, forward_args->d); |
| | mj_factorM(forward_args->m, forward_args->d); |
| | return NULL; |
| | } |
| |
|
| | |
| | void* mj_collisionThreaded(void* args) { |
| | mjFwdPositionArgs* forward_args = (mjFwdPositionArgs*) args; |
| | mj_collision(forward_args->m, forward_args->d); |
| | return NULL; |
| | } |
| |
|
| |
|
| |
|
| | |
| | void mj_fwdPosition(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); |
| |
|
| | |
| | if (!d->threadpool) { |
| | |
| | mj_makeM(m, d); |
| | mj_factorM(m, d); |
| |
|
| | |
| | mj_collision(m, d); |
| | } |
| |
|
| | |
| | else { |
| | mjTask tasks[2]; |
| | mjFwdPositionArgs forward_args; |
| | forward_args.m = m; |
| | forward_args.d = d; |
| |
|
| | mju_defaultTask(&tasks[0]); |
| | tasks[0].func = mj_inertialThreaded; |
| | tasks[0].args = &forward_args; |
| | mju_threadPoolEnqueue((mjThreadPool*)d->threadpool, &tasks[0]); |
| |
|
| | mju_defaultTask(&tasks[1]); |
| | tasks[1].func = mj_collisionThreaded; |
| | tasks[1].args = &forward_args; |
| | mju_threadPoolEnqueue((mjThreadPool*)d->threadpool, &tasks[1]); |
| |
|
| | mju_taskJoin(&tasks[0]); |
| | mju_taskJoin(&tasks[1]); |
| | } |
| |
|
| | TM_RESTART; |
| | mj_makeConstraint(m, d); |
| | mj_island(m, d); |
| | TM_END(mjTIMER_POS_MAKE); |
| |
|
| | TM_RESTART; |
| | mj_transmission(m, d); |
| | TM_ADD(mjTIMER_POS_KINEMATICS); |
| |
|
| | TM_RESTART; |
| | mj_projectConstraint(m, d); |
| | TM_END(mjTIMER_POS_PROJECT); |
| |
|
| | TM_END1(mjTIMER_POSITION); |
| | } |
| |
|
| |
|
| |
|
| | |
| | void mj_fwdVelocity(const mjModel* m, mjData* d) { |
| | TM_START; |
| |
|
| | |
| | if (mj_isSparse(m)) { |
| | mju_mulMatVecSparse(d->flexedge_velocity, d->flexedge_J, d->qvel, m->nflexedge, |
| | d->flexedge_J_rownnz, d->flexedge_J_rowadr, d->flexedge_J_colind, NULL); |
| | } else { |
| | mju_mulMatVec(d->flexedge_velocity, d->flexedge_J, d->qvel, m->nflexedge, m->nv); |
| | } |
| |
|
| | |
| | if (mj_isSparse(m)) { |
| | mju_mulMatVecSparse(d->ten_velocity, d->ten_J, d->qvel, m->ntendon, |
| | d->ten_J_rownnz, d->ten_J_rowadr, d->ten_J_colind, NULL); |
| | } else { |
| | mju_mulMatVec(d->ten_velocity, d->ten_J, d->qvel, m->ntendon, m->nv); |
| | } |
| |
|
| | |
| | if (!mjDISABLED(mjDSBL_ACTUATION)) { |
| | mju_mulMatVecSparse(d->actuator_velocity, d->actuator_moment, d->qvel, m->nu, |
| | d->moment_rownnz, d->moment_rowadr, d->moment_colind, NULL); |
| | } |
| |
|
| | |
| | mj_comVel(m, d); |
| | mj_passive(m, d); |
| | mj_referenceConstraint(m, d); |
| |
|
| | |
| | mj_rne(m, d, 0, d->qfrc_bias); |
| |
|
| | |
| | mj_tendonBias(m, d, d->qfrc_bias); |
| |
|
| | TM_END(mjTIMER_VELOCITY); |
| | } |
| |
|
| |
|
| |
|
| | |
| | static mjtNum nextActivation(const mjModel* m, const mjData* d, |
| | int actuator_id, int act_adr, mjtNum act_dot) { |
| | mjtNum act = d->act[act_adr]; |
| |
|
| | if (m->actuator_dyntype[actuator_id] == mjDYN_FILTEREXACT) { |
| | |
| | |
| | |
| | |
| | mjtNum tau = mju_max(mjMINVAL, m->actuator_dynprm[actuator_id * mjNDYN]); |
| | act = act + act_dot * tau * (1 - mju_exp(-m->opt.timestep / tau)); |
| | } else { |
| | |
| | act = act + act_dot * m->opt.timestep; |
| | } |
| |
|
| | |
| | if (m->actuator_actlimited[actuator_id]) { |
| | mjtNum* actrange = m->actuator_actrange + 2 * actuator_id; |
| | act = mju_clip(act, actrange[0], actrange[1]); |
| | } |
| |
|
| | return act; |
| | } |
| |
|
| |
|
| |
|
| | |
| | static void clampVec(mjtNum* vec, const mjtNum* range, const mjtByte* limited, int n, |
| | const int* index) { |
| | for (int i=0; i < n; i++) { |
| | int j = index ? index[i] : i; |
| | if (limited[i]) { |
| | vec[j] = mju_clip(vec[j], range[2*i], range[2*i + 1]); |
| | } |
| | } |
| | } |
| |
|
| |
|
| |
|
| | |
| | void mj_fwdActuation(const mjModel* m, mjData* d) { |
| | TM_START; |
| | int nv = m->nv, nu = m->nu, ntendon = m->ntendon; |
| | mjtNum gain, bias, tau; |
| | mjtNum *prm, *force = d->actuator_force; |
| |
|
| | |
| | mju_zero(force, nu); |
| |
|
| | |
| | if (nu == 0 || mjDISABLED(mjDSBL_ACTUATION)) { |
| | mju_zero(d->qfrc_actuator, nv); |
| | return; |
| | } |
| |
|
| | |
| | int tendon_frclimited = 0; |
| |
|
| | |
| | mj_markStack(d); |
| | mjtNum *ctrl = mjSTACKALLOC(d, nu, mjtNum); |
| | mju_copy(ctrl, d->ctrl, nu); |
| | if (!mjDISABLED(mjDSBL_CLAMPCTRL)) { |
| | clampVec(ctrl, m->actuator_ctrlrange, m->actuator_ctrllimited, nu, NULL); |
| | } |
| |
|
| | |
| | for (int i=0; i < nu; i++) { |
| | if (mju_isBad(ctrl[i])) { |
| | mj_warning(d, mjWARN_BADCTRL, i); |
| | mju_zero(ctrl, nu); |
| | break; |
| | } |
| | } |
| |
|
| | |
| | for (int i=0; i < nu; i++) { |
| | int act_first = m->actuator_actadr[i]; |
| | if (act_first < 0) { |
| | continue; |
| | } |
| |
|
| | |
| | if (m->actuator_actnum[i]) { |
| | mju_zero(d->act_dot + act_first, m->actuator_actnum[i]); |
| | } |
| |
|
| | |
| | prm = m->actuator_dynprm + i*mjNDYN; |
| |
|
| | |
| | |
| | int act_last = act_first + m->actuator_actnum[i] - 1; |
| |
|
| | |
| | switch ((mjtDyn) m->actuator_dyntype[i]) { |
| | case mjDYN_INTEGRATOR: |
| | d->act_dot[act_last] = ctrl[i]; |
| | break; |
| |
|
| | case mjDYN_FILTER: |
| | case mjDYN_FILTEREXACT: |
| | tau = mju_max(mjMINVAL, prm[0]); |
| | d->act_dot[act_last] = (ctrl[i] - d->act[act_last]) / tau; |
| | break; |
| |
|
| | case mjDYN_MUSCLE: |
| | d->act_dot[act_last] = mju_muscleDynamics( |
| | ctrl[i], d->act[act_last], prm); |
| | break; |
| |
|
| | default: |
| | if (mjcb_act_dyn) { |
| | if (m->actuator_actnum[i] == 1) { |
| | |
| | d->act_dot[act_last] = mjcb_act_dyn(m, d, i); |
| | } else { |
| | |
| | mjcb_act_dyn(m, d, i); |
| | } |
| | } |
| | } |
| | } |
| |
|
| | |
| | if (m->nplugin) { |
| | const int nslot = mjp_pluginCount(); |
| | for (int i=0; i < m->nplugin; i++) { |
| | const int slot = m->plugin[i]; |
| | const mjpPlugin* plugin = mjp_getPluginAtSlotUnsafe(slot, nslot); |
| | if (!plugin) { |
| | mjERROR("invalid plugin slot: %d", slot); |
| | } |
| | if (plugin->capabilityflags & mjPLUGIN_ACTUATOR) { |
| | if (plugin->actuator_act_dot) { |
| | plugin->actuator_act_dot(m, d, i); |
| | } |
| | } |
| | } |
| | } |
| |
|
| | |
| | for (int i=0; i < nu; i++) { |
| | |
| | if (mj_actuatorDisabled(m, i)) { |
| | continue; |
| | } |
| |
|
| | |
| | if (m->actuator_plugin[i] >= 0) { |
| | continue; |
| | } |
| |
|
| | |
| | if (ntendon && !tendon_frclimited && m->actuator_trntype[i] == mjTRN_TENDON) { |
| | tendon_frclimited = m->tendon_actfrclimited[m->actuator_trnid[2*i]]; |
| | } |
| |
|
| | |
| | prm = m->actuator_gainprm + mjNGAIN*i; |
| |
|
| | |
| | switch ((mjtGain) m->actuator_gaintype[i]) { |
| | case mjGAIN_FIXED: |
| | gain = prm[0]; |
| | break; |
| |
|
| | case mjGAIN_AFFINE: |
| | gain = prm[0] + prm[1]*d->actuator_length[i] + prm[2]*d->actuator_velocity[i]; |
| | break; |
| |
|
| | case mjGAIN_MUSCLE: |
| | gain = mju_muscleGain(d->actuator_length[i], |
| | d->actuator_velocity[i], |
| | m->actuator_lengthrange+2*i, |
| | m->actuator_acc0[i], |
| | prm); |
| | break; |
| |
|
| | default: |
| | if (mjcb_act_gain) { |
| | gain = mjcb_act_gain(m, d, i); |
| | } else { |
| | gain = 1; |
| | } |
| | } |
| |
|
| | |
| | if (m->actuator_actadr[i] == -1) { |
| | force[i] = gain * ctrl[i]; |
| | } else { |
| | |
| | int act_adr = m->actuator_actadr[i] + m->actuator_actnum[i] - 1; |
| |
|
| | mjtNum act; |
| | if (m->actuator_actearly[i]) { |
| | act = nextActivation(m, d, i, act_adr, d->act_dot[act_adr]); |
| | } else { |
| | act = d->act[act_adr]; |
| | } |
| | force[i] = gain * act; |
| | } |
| |
|
| | |
| | prm = m->actuator_biasprm + mjNBIAS*i; |
| |
|
| | |
| | switch ((mjtBias) m->actuator_biastype[i]) { |
| | case mjBIAS_NONE: |
| | bias = 0.0; |
| | break; |
| |
|
| | case mjBIAS_AFFINE: |
| | bias = prm[0] + prm[1]*d->actuator_length[i] + prm[2]*d->actuator_velocity[i]; |
| | break; |
| |
|
| | case mjBIAS_MUSCLE: |
| | bias = mju_muscleBias(d->actuator_length[i], |
| | m->actuator_lengthrange+2*i, |
| | m->actuator_acc0[i], |
| | prm); |
| | break; |
| |
|
| | default: |
| | if (mjcb_act_bias) { |
| | bias = mjcb_act_bias(m, d, i); |
| | } else { |
| | bias = 0; |
| | } |
| | } |
| |
|
| | |
| | force[i] += bias; |
| | } |
| |
|
| | |
| | if (m->nplugin) { |
| | const int nslot = mjp_pluginCount(); |
| | for (int i=0; i < m->nplugin; i++) { |
| | const int slot = m->plugin[i]; |
| | const mjpPlugin* plugin = mjp_getPluginAtSlotUnsafe(slot, nslot); |
| | if (!plugin) { |
| | mjERROR("invalid plugin slot: %d", slot); |
| | } |
| | if (plugin->capabilityflags & mjPLUGIN_ACTUATOR) { |
| | if (!plugin->compute) { |
| | mjERROR("`compute` is a null function pointer for plugin at slot %d", slot); |
| | } |
| | plugin->compute(m, d, i, mjPLUGIN_ACTUATOR); |
| | } |
| | } |
| | } |
| |
|
| | |
| | if (tendon_frclimited) { |
| | |
| | mjtNum* tendon_total_force = mjSTACKALLOC(d, ntendon, mjtNum); |
| | mju_zero(tendon_total_force, ntendon); |
| | for (int i=0; i < nu; i++) { |
| | if (m->actuator_trntype[i] == mjTRN_TENDON) { |
| | int tendon_id = m->actuator_trnid[2*i]; |
| | if (m->tendon_actfrclimited[tendon_id]) { |
| | tendon_total_force[tendon_id] += force[i]; |
| | } |
| | } |
| | } |
| |
|
| | |
| | for (int i=0; i < nu; i++) { |
| | if (m->actuator_trntype[i] != mjTRN_TENDON) { |
| | continue; |
| | } |
| | int tendon_id = m->actuator_trnid[2*i]; |
| | mjtNum tendon_force = tendon_total_force[tendon_id]; |
| | if (m->tendon_actfrclimited[tendon_id] && tendon_force) { |
| | const mjtNum* range = m->tendon_actfrcrange + 2 * tendon_id; |
| | if (tendon_force < range[0]) { |
| | force[i] *= range[0] / tendon_force; |
| | } else if (tendon_force > range[1]) { |
| | force[i] *= range[1] / tendon_force; |
| | } |
| | } |
| | } |
| | } |
| |
|
| | |
| | clampVec(force, m->actuator_forcerange, m->actuator_forcelimited, nu, NULL); |
| |
|
| | |
| | mju_mulMatTVecSparse(d->qfrc_actuator, d->actuator_moment, force, nu, nv, |
| | d->moment_rownnz, d->moment_rowadr, d->moment_colind); |
| |
|
| | |
| | if (m->ngravcomp && !mjDISABLED(mjDSBL_GRAVITY) && mju_norm3(m->opt.gravity)) { |
| | |
| | static const int jnt_dofnum[4] = {6, 3, 1, 1}; |
| | int njnt = m->njnt; |
| | for (int i=0; i < njnt; i++) { |
| | |
| | if (!m->jnt_actgravcomp[i]) { |
| | continue; |
| | } |
| |
|
| | |
| | int dofnum = jnt_dofnum[m->jnt_type[i]]; |
| | int dofadr = m->jnt_dofadr[i]; |
| | mju_addTo(d->qfrc_actuator + dofadr, d->qfrc_gravcomp + dofadr, dofnum); |
| | } |
| | } |
| |
|
| | |
| | clampVec(d->qfrc_actuator, m->jnt_actfrcrange, m->jnt_actfrclimited, m->njnt, m->jnt_dofadr); |
| |
|
| | mj_freeStack(d); |
| | TM_END(mjTIMER_ACTUATION); |
| | } |
| |
|
| |
|
| |
|
| | |
| | void mj_fwdAcceleration(const mjModel* m, mjData* d) { |
| | int nv = m->nv; |
| |
|
| | |
| | mju_sub(d->qfrc_smooth, d->qfrc_passive, d->qfrc_bias, nv); |
| | mju_addTo(d->qfrc_smooth, d->qfrc_applied, nv); |
| | mju_addTo(d->qfrc_smooth, d->qfrc_actuator, nv); |
| | mj_xfrcAccumulate(m, d, d->qfrc_smooth); |
| |
|
| | |
| | mj_solveM(m, d, d->qacc_smooth, d->qfrc_smooth, 1); |
| | } |
| |
|
| |
|
| |
|
| | |
| | static void warmstart(const mjModel* m, mjData* d) { |
| | int nv = m->nv, nefc = d->nefc; |
| |
|
| | |
| | if (!mjDISABLED(mjDSBL_WARMSTART)) { |
| | mj_markStack(d); |
| | mjtNum* jar = mjSTACKALLOC(d, nefc, mjtNum); |
| |
|
| | |
| | mju_copy(d->qacc, d->qacc_warmstart, nv); |
| |
|
| | |
| | mj_mulJacVec(m, d, jar, d->qacc_warmstart); |
| | mju_subFrom(jar, d->efc_aref, nefc); |
| |
|
| | |
| | mjtNum cost_warmstart; |
| | mj_constraintUpdate(m, d, jar, &cost_warmstart, 0); |
| |
|
| | |
| | if (m->opt.solver == mjSOL_PGS) { |
| | |
| | mjtNum PGS_warmstart = mju_dot(d->efc_force, d->efc_b, nefc); |
| | mjtNum* ARf = mjSTACKALLOC(d, nefc, mjtNum); |
| | if (mj_isSparse(m)) |
| | mju_mulMatVecSparse(ARf, d->efc_AR, d->efc_force, nefc, |
| | d->efc_AR_rownnz, d->efc_AR_rowadr, |
| | d->efc_AR_colind, NULL); |
| | else { |
| | mju_mulMatVec(ARf, d->efc_AR, d->efc_force, nefc, nefc); |
| | } |
| | PGS_warmstart += 0.5*mju_dot(d->efc_force, ARf, nefc); |
| |
|
| | |
| | if (PGS_warmstart > 0) { |
| | mju_zero(d->efc_force, nefc); |
| | mju_zero(d->qfrc_constraint, nv); |
| | } |
| | } |
| |
|
| | |
| | else { |
| | |
| | mjtNum* Ma = mjSTACKALLOC(d, nv, mjtNum); |
| | mj_mulM(m, d, Ma, d->qacc_warmstart); |
| | for (int i=0; i < nv; i++) { |
| | cost_warmstart += 0.5*(Ma[i]-d->qfrc_smooth[i])*(d->qacc_warmstart[i]-d->qacc_smooth[i]); |
| | } |
| |
|
| | |
| | mjtNum cost_smooth; |
| | mj_constraintUpdate(m, d, d->efc_b, &cost_smooth, 0); |
| |
|
| | |
| | if (cost_warmstart > cost_smooth) { |
| | mju_copy(d->qacc, d->qacc_smooth, nv); |
| | } |
| | } |
| |
|
| | |
| | if (d->nisland > 0) { |
| | |
| | for (int i=d->nidof; i < nv; i++) { |
| | int dof = d->map_idof2dof[i]; |
| | d->qacc[dof] = d->qacc_smooth[dof]; |
| | } |
| | } |
| |
|
| | mj_freeStack(d); |
| | } |
| |
|
| | |
| | else { |
| | mju_copy(d->qacc, d->qacc_smooth, nv); |
| | mju_zero(d->efc_force, nefc); |
| | } |
| | } |
| |
|
| |
|
| |
|
| | |
| | struct mjSolIslandArgs_ { |
| | const mjModel* m; |
| | mjData* d; |
| | int island; |
| | }; |
| | typedef struct mjSolIslandArgs_ mjSolIslandArgs; |
| |
|
| | |
| | static void* CG_wrapper(void* args) { |
| | mjSolIslandArgs* solargs = (mjSolIslandArgs*) args; |
| | mj_solCG_island(solargs->m, solargs->d, solargs->island, solargs->m->opt.iterations); |
| | return NULL; |
| | } |
| |
|
| | |
| | static void* Newton_wrapper(void* args) { |
| | mjSolIslandArgs* solargs = (mjSolIslandArgs*) args; |
| | mj_solNewton_island(solargs->m, solargs->d, solargs->island, solargs->m->opt.iterations); |
| | return NULL; |
| | } |
| |
|
| | |
| | static void solve_threaded(const mjModel* m, mjData* d, int flg_Newton) { |
| | mj_markStack(d); |
| | |
| | mjSolIslandArgs* sol_island_args = mjSTACKALLOC(d, d->nisland, mjSolIslandArgs); |
| | mjTask* tasks = mjSTACKALLOC(d, d->nisland, mjTask); |
| |
|
| | for (int island = 0; island < d->nisland; ++island) { |
| | sol_island_args[island].m = m; |
| | sol_island_args[island].d = d; |
| | sol_island_args[island].island = island; |
| |
|
| | mju_defaultTask(&tasks[island]); |
| | tasks[island].func = flg_Newton ? Newton_wrapper : CG_wrapper; |
| | tasks[island].args = &sol_island_args[island]; |
| | mju_threadPoolEnqueue((mjThreadPool*)d->threadpool, &tasks[island]); |
| | } |
| |
|
| | for (int island = 0; island < d->nisland; ++island) { |
| | mju_taskJoin(&tasks[island]); |
| | } |
| |
|
| | mj_freeStack(d); |
| | } |
| |
|
| |
|
| |
|
| | |
| | void mj_fwdConstraint(const mjModel* m, mjData* d) { |
| | TM_START; |
| | int nv = m->nv, nefc = d->nefc, nisland = d->nisland; |
| |
|
| | |
| | mju_zero(d->qfrc_constraint, nv); |
| |
|
| | |
| | if (!nefc) { |
| | mju_copy(d->qacc, d->qacc_smooth, nv); |
| | mju_copy(d->qacc_warmstart, d->qacc_smooth, nv); |
| | mju_zeroInt(d->solver_niter, mjNISLAND); |
| | TM_END(mjTIMER_CONSTRAINT); |
| | return; |
| | } |
| |
|
| | |
| | mj_mulJacVec(m, d, d->efc_b, d->qacc_smooth); |
| | mju_subFrom(d->efc_b, d->efc_aref, nefc); |
| |
|
| | |
| | warmstart(m, d); |
| | mju_zeroInt(d->solver_niter, mjNISLAND); |
| |
|
| | |
| | int islands_supported = mjENABLED(mjENBL_ISLAND) && |
| | nisland > 0 && |
| | m->opt.noslip_iterations == 0 && |
| | (m->opt.solver == mjSOL_CG || m->opt.solver == mjSOL_NEWTON); |
| |
|
| | |
| | if (islands_supported) { |
| | int nidof = d->nidof; |
| |
|
| | |
| | mju_gather(d->ifrc_smooth, d->qfrc_smooth, d->map_idof2dof, nidof); |
| | mju_gather(d->ifrc_constraint, d->qfrc_constraint, d->map_idof2dof, nidof); |
| | mju_gather(d->iacc_smooth, d->qacc_smooth, d->map_idof2dof, nidof); |
| | mju_gather(d->iacc, d->qacc, d->map_idof2dof, nidof); |
| | mju_gather(d->iefc_force, d->efc_force, d->map_iefc2efc, nefc); |
| | mju_gather(d->iefc_aref, d->efc_aref, d->map_iefc2efc, nefc); |
| |
|
| | |
| | if (!d->threadpool) { |
| | |
| | for (int island=0; island < nisland; island++) { |
| | if (m->opt.solver == mjSOL_NEWTON) { |
| | mj_solNewton_island(m, d, island, m->opt.iterations); |
| | } else { |
| | mj_solCG_island(m, d, island, m->opt.iterations); |
| | } |
| | } |
| | } else { |
| | |
| | solve_threaded(m, d, m->opt.solver == mjSOL_NEWTON); |
| | } |
| |
|
| |
|
| | |
| | mju_scatter(d->qacc, d->iacc, d->map_idof2dof, nidof); |
| | mju_scatter(d->qfrc_constraint, d->ifrc_constraint, d->map_idof2dof, nidof); |
| | mju_gather(d->efc_force, d->iefc_force, d->map_efc2iefc, nefc); |
| | } |
| |
|
| | |
| | else { |
| | switch ((mjtSolver) m->opt.solver) { |
| | case mjSOL_PGS: |
| | mj_solPGS(m, d, m->opt.iterations); |
| | break; |
| |
|
| | case mjSOL_CG: |
| | mj_solCG(m, d, m->opt.iterations); |
| | break; |
| |
|
| | case mjSOL_NEWTON: |
| | mj_solNewton(m, d, m->opt.iterations); |
| | break; |
| |
|
| | default: |
| | mjERROR("unknown solver type %d", m->opt.solver); |
| | } |
| | } |
| |
|
| | |
| | mju_copy(d->qacc_warmstart, d->qacc, nv); |
| |
|
| | |
| | if (m->opt.noslip_iterations > 0) { |
| | mj_solNoSlip(m, d, m->opt.noslip_iterations); |
| | } |
| |
|
| | TM_END(mjTIMER_CONSTRAINT); |
| | } |
| |
|
| |
|
| |
|
| | |
| |
|
| | |
| | static void mj_advance(const mjModel* m, mjData* d, |
| | const mjtNum* act_dot, const mjtNum* qacc, const mjtNum* qvel) { |
| | |
| | if (m->na && !mjDISABLED(mjDSBL_ACTUATION)) { |
| | int nu = m->nu; |
| | for (int i=0; i < nu; i++) { |
| | int actadr = m->actuator_actadr[i]; |
| | int actadr_end = actadr + m->actuator_actnum[i]; |
| | for (int j=actadr; j < actadr_end; j++) { |
| | |
| | d->act[j] = nextActivation(m, d, i, j, mj_actuatorDisabled(m, i) ? 0 : act_dot[j]); |
| | } |
| | } |
| | } |
| |
|
| | |
| | mju_addToScl(d->qvel, qacc, m->opt.timestep, m->nv); |
| |
|
| | |
| | mj_integratePos(m, d->qpos, qvel ? qvel : d->qvel, m->opt.timestep); |
| |
|
| | |
| | d->time += m->opt.timestep; |
| |
|
| | |
| | if (m->nplugin) { |
| | const int nslot = mjp_pluginCount(); |
| | for (int i = 0; i < m->nplugin; ++i) { |
| | const int slot = m->plugin[i]; |
| | const mjpPlugin* plugin = mjp_getPluginAtSlotUnsafe(slot, nslot); |
| | if (!plugin) { |
| | mjERROR("invalid plugin slot: %d", slot); |
| | } |
| | if (plugin->advance) { |
| | plugin->advance(m, d, i); |
| | } |
| | } |
| | } |
| | } |
| |
|
| | |
| | void mj_EulerSkip(const mjModel* m, mjData* d, int skipfactor) { |
| | TM_START; |
| | int nv = m->nv, nC = m->nC; |
| | mj_markStack(d); |
| | mjtNum* qfrc = mjSTACKALLOC(d, nv, mjtNum); |
| | mjtNum* qacc = mjSTACKALLOC(d, nv, mjtNum); |
| |
|
| | |
| | int 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) { |
| | mju_copy(qacc, d->qacc, nv); |
| | } |
| |
|
| | |
| | else { |
| | if (!skipfactor) { |
| | |
| | mju_copy(d->qH, d->M, nC); |
| | for (int i=0; i < nv; i++) { |
| | d->qH[d->M_rowadr[i] + d->M_rownnz[i] - 1] += m->opt.timestep * m->dof_damping[i]; |
| | } |
| |
|
| | |
| | mj_factorI(d->qH, d->qHDiagInv, nv, d->M_rownnz, d->M_rowadr, d->M_colind); |
| | } |
| |
|
| | |
| | mju_add(qfrc, d->qfrc_smooth, d->qfrc_constraint, nv); |
| | mju_copy(qacc, qfrc, m->nv); |
| | mj_solveLD(qacc, d->qH, d->qHDiagInv, nv, 1, |
| | d->M_rownnz, d->M_rowadr, d->M_colind); |
| | } |
| |
|
| | |
| | mj_advance(m, d, d->act_dot, qacc, NULL); |
| |
|
| | mj_freeStack(d); |
| |
|
| | TM_END(mjTIMER_ADVANCE); |
| | } |
| |
|
| |
|
| |
|
| | |
| | void mj_Euler(const mjModel* m, mjData* d) { |
| | mj_EulerSkip(m, d, 0); |
| | } |
| |
|
| |
|
| |
|
| | |
| | const mjtNum RK4_A[9] = { |
| | 0.5, 0, 0, |
| | 0, 0.5, 0, |
| | 0, 0, 1 |
| | }; |
| |
|
| | const mjtNum RK4_B[4] = { |
| | 1.0/6.0, 1.0/3.0, 1.0/3.0, 1.0/6.0 |
| | }; |
| |
|
| |
|
| | |
| | |
| | void mj_RungeKutta(const mjModel* m, mjData* d, int N) { |
| | int nv = m->nv, nq = m->nq, na = m->na; |
| | mjtNum h = m->opt.timestep, time = d->time; |
| | mjtNum C[9], T[9], *X[10], *F[10], *dX; |
| | const mjtNum* A = (N == 4 ? RK4_A : 0); |
| | const mjtNum* B = (N == 4 ? RK4_B : 0); |
| |
|
| | |
| | if (!A) { |
| | mjERROR("supported RK orders: N=4"); |
| | } |
| |
|
| | |
| | mj_markStack(d); |
| | dX = mjSTACKALLOC(d, 2*nv+na, mjtNum); |
| | for (int i=0; i < N; i++) { |
| | X[i] = mjSTACKALLOC(d, nq+nv+na, mjtNum); |
| | F[i] = mjSTACKALLOC(d, nv+na, mjtNum); |
| | } |
| |
|
| | |
| | for (int i=1; i < N; i++) { |
| | |
| | C[i-1] = 0; |
| | for (int j=0; j < i; j++) { |
| | C[i-1] += A[(i-1)*(N-1)+j]; |
| | } |
| |
|
| | |
| | T[i-1] = d->time + C[i-1]*h; |
| | } |
| |
|
| | |
| | mju_copy(X[0], d->qpos, nq); |
| | mju_copy(X[0]+nq, d->qvel, nv); |
| | mju_copy(F[0], d->qacc, nv); |
| | if (na) { |
| | mju_copy(X[0]+nq+nv, d->act, na); |
| | mju_copy(F[0]+nv, d->act_dot, na); |
| | } |
| |
|
| | |
| | for (int i=1; i < N; i++) { |
| | |
| | mju_zero(dX, 2*nv+na); |
| | for (int j=0; j < i; j++) { |
| | mju_addToScl(dX, X[j]+nq, A[(i-1)*(N-1)+j], nv); |
| | mju_addToScl(dX+nv, F[j], A[(i-1)*(N-1)+j], nv+na); |
| | } |
| |
|
| | |
| | mju_copy(X[i], X[0], nq+nv+na); |
| | mj_integratePos(m, X[i], dX, h); |
| | mju_addToScl(X[i]+nq, dX+nv, h, nv+na); |
| |
|
| | |
| | mju_copy(d->qpos, X[i], nq); |
| | mju_copy(d->qvel, X[i]+nq, nv); |
| | if (na) { |
| | mju_copy(d->act, X[i]+nq+nv, na); |
| | } |
| | d->time = T[i-1]; |
| |
|
| | |
| | mj_forwardSkip(m, d, mjSTAGE_NONE, 1); |
| | mju_copy(F[i], d->qacc, nv); |
| | if (na) { |
| | mju_copy(F[i]+nv, d->act_dot, na); |
| | } |
| | } |
| |
|
| | |
| | mju_zero(dX, 2*nv+na); |
| | for (int j=0; j < N; j++) { |
| | mju_addToScl(dX, X[j]+nq, B[j], nv); |
| | mju_addToScl(dX+nv, F[j], B[j], nv+na); |
| | } |
| |
|
| | |
| | d->time = time; |
| | mju_copy(d->qpos, X[0], nq); |
| | mju_copy(d->qvel, X[0]+nq, nv); |
| | mju_copy(d->act, X[0]+nq+nv, na); |
| |
|
| | |
| | mj_advance(m, d, dX+2*nv, dX+nv, dX); |
| |
|
| | mj_freeStack(d); |
| | } |
| |
|
| |
|
| |
|
| | |
| | void mj_implicitSkip(const mjModel* m, mjData* d, int skipfactor) { |
| | TM_START; |
| | int nv = m->nv, nM = m->nM, nD = m->nD, nC = m->nC; |
| |
|
| | mj_markStack(d); |
| | mjtNum* qfrc = mjSTACKALLOC(d, nv, mjtNum); |
| | mjtNum* qacc = mjSTACKALLOC(d, nv, mjtNum); |
| |
|
| | |
| | mju_add(qfrc, d->qfrc_smooth, d->qfrc_constraint, nv); |
| |
|
| | |
| | if (m->opt.integrator == mjINT_IMPLICIT) { |
| | if (!skipfactor) { |
| | |
| | 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); |
| |
|
| | |
| | int* scratch = mjSTACKALLOC(d, nv, int); |
| | mju_factorLUSparse(d->qLU, nv, scratch, d->D_rownnz, d->D_rowadr, d->D_colind); |
| | } |
| |
|
| | |
| | mju_solveLUSparse(qacc, d->qLU, qfrc, nv, d->D_rownnz, d->D_rowadr, d->D_diag, d->D_colind); |
| | } |
| |
|
| | |
| | else if (m->opt.integrator == mjINT_IMPLICITFAST) { |
| | if (!skipfactor) { |
| | |
| | mjd_smooth_vel(m, d, 0); |
| |
|
| | |
| | mjtNum* MhB = mjSTACKALLOC(d, nM, mjtNum); |
| | mju_gather(MhB, d->qDeriv, d->mapD2M, nM); |
| |
|
| | |
| | mju_addScl(MhB, d->qM, MhB, -m->opt.timestep, nM); |
| |
|
| | |
| | mju_gather(d->qH, MhB, d->mapM2M, nC); |
| |
|
| | |
| | mj_factorI(d->qH, d->qHDiagInv, nv, d->M_rownnz, d->M_rowadr, d->M_colind); |
| | } |
| |
|
| | |
| | mju_copy(qacc, qfrc, nv); |
| | mj_solveLD(qacc, d->qH, d->qHDiagInv, nv, 1, |
| | d->M_rownnz, d->M_rowadr, d->M_colind); |
| |
|
| | } else { |
| | mjERROR("integrator must be implicit or implicitfast"); |
| | } |
| |
|
| | |
| | mj_advance(m, d, d->act_dot, qacc, NULL); |
| |
|
| | mj_freeStack(d); |
| |
|
| | TM_END(mjTIMER_ADVANCE); |
| | } |
| |
|
| |
|
| |
|
| | |
| | void mj_implicit(const mjModel* m, mjData* d) { |
| | mj_implicitSkip(m, d, 0); |
| | } |
| |
|
| |
|
| |
|
| | |
| | static int energyPosSensor(const mjModel* m) { |
| | if (mjDISABLED(mjDSBL_SENSOR)) { |
| | return 0; |
| | } |
| |
|
| | for (int i=0; i < m->nsensor; i++) { |
| | if (m->sensor_type[i] == mjSENS_E_POTENTIAL) { |
| | return 1; |
| | } |
| | } |
| | return 0; |
| | } |
| |
|
| |
|
| |
|
| | |
| | static int energyVelSensor(const mjModel* m) { |
| | if (mjDISABLED(mjDSBL_SENSOR)) { |
| | return 0; |
| | } |
| |
|
| | for (int i=0; i < m->nsensor; i++) { |
| | if (m->sensor_type[i] == mjSENS_E_KINETIC) { |
| | return 1; |
| | } |
| | } |
| | return 0; |
| | } |
| |
|
| |
|
| |
|
| | |
| |
|
| | |
| | void mj_forwardSkip(const mjModel* m, mjData* d, int skipstage, int skipsensor) { |
| | TM_START; |
| |
|
| | |
| | if (skipstage < mjSTAGE_POS) { |
| | mj_fwdPosition(m, d); |
| |
|
| | int energyPos = 0; |
| | if (!skipsensor) { |
| | mj_sensorPos(m, d); |
| | energyPos = energyPosSensor(m); |
| | } |
| |
|
| | if (!energyPos) { |
| | if (mjENABLED(mjENBL_ENERGY)) { |
| | mj_energyPos(m, d); |
| | } else { |
| | d->energy[0] = d->energy[1] = 0; |
| | } |
| | } |
| | } |
| |
|
| | |
| | if (skipstage < mjSTAGE_VEL) { |
| | mj_fwdVelocity(m, d); |
| |
|
| | int energyVel = 0; |
| | if (!skipsensor) { |
| | mj_sensorVel(m, d); |
| | energyVel = energyVelSensor(m); |
| | } |
| |
|
| | if (mjENABLED(mjENBL_ENERGY) && !energyVel) { |
| | mj_energyVel(m, d); |
| | } |
| | } |
| |
|
| | |
| | if (mjcb_control && !mjDISABLED(mjDSBL_ACTUATION)) { |
| | mjcb_control(m, d); |
| | } |
| |
|
| | mj_fwdActuation(m, d); |
| | mj_fwdAcceleration(m, d); |
| | mj_fwdConstraint(m, d); |
| | if (!skipsensor) { |
| | mj_sensorAcc(m, d); |
| | } |
| |
|
| | TM_END(mjTIMER_FORWARD); |
| | } |
| |
|
| |
|
| |
|
| | |
| | void mj_forward(const mjModel* m, mjData* d) { |
| | mj_forwardSkip(m, d, mjSTAGE_NONE, 0); |
| | } |
| |
|
| |
|
| |
|
| | |
| | void mj_step(const mjModel* m, mjData* d) { |
| | TM_START; |
| |
|
| | |
| | mj_checkPos(m, d); |
| | mj_checkVel(m, d); |
| | mj_forward(m, d); |
| | mj_checkAcc(m, d); |
| |
|
| | |
| | if (mjENABLED(mjENBL_FWDINV)) { |
| | mj_compareFwdInv(m, d); |
| | } |
| |
|
| | |
| | switch ((mjtIntegrator) m->opt.integrator) { |
| | case mjINT_EULER: |
| | mj_Euler(m, d); |
| | break; |
| |
|
| | case mjINT_RK4: |
| | mj_RungeKutta(m, d, 4); |
| | break; |
| |
|
| | case mjINT_IMPLICIT: |
| | case mjINT_IMPLICITFAST: |
| | mj_implicit(m, d); |
| | break; |
| |
|
| | default: |
| | mjERROR("invalid integrator"); |
| | } |
| |
|
| | TM_END(mjTIMER_STEP); |
| | } |
| |
|
| |
|
| |
|
| | |
| | void mj_step1(const mjModel* m, mjData* d) { |
| | TM_START; |
| | mj_checkPos(m, d); |
| | mj_checkVel(m, d); |
| | mj_fwdPosition(m, d); |
| | mj_sensorPos(m, d); |
| | if (!energyPosSensor(m)) { |
| | if (mjENABLED(mjENBL_ENERGY)) { |
| | mj_energyPos(m, d); |
| | } else { |
| | d->energy[0] = d->energy[1] = 0; |
| | } |
| | } |
| | mj_fwdVelocity(m, d); |
| | mj_sensorVel(m, d); |
| | if (mjENABLED(mjENBL_ENERGY) && !energyVelSensor(m)) { |
| | mj_energyVel(m, d); |
| | } |
| | if (mjcb_control) { |
| | mjcb_control(m, d); |
| | } |
| | TM_END(mjTIMER_STEP); |
| | } |
| |
|
| |
|
| | |
| |
|
| |
|
| | |
| | void mj_step2(const mjModel* m, mjData* d) { |
| | TM_START; |
| | mj_fwdActuation(m, d); |
| | mj_fwdAcceleration(m, d); |
| | mj_fwdConstraint(m, d); |
| | mj_sensorAcc(m, d); |
| | mj_checkAcc(m, d); |
| |
|
| | |
| | if (mjENABLED(mjENBL_FWDINV)) { |
| | mj_compareFwdInv(m, d); |
| | } |
| |
|
| | |
| | if (m->opt.integrator == mjINT_IMPLICIT || m->opt.integrator == mjINT_IMPLICITFAST) { |
| | mj_implicit(m, d); |
| | } else { |
| | mj_Euler(m, d); |
| | } |
| |
|
| | d->timer[mjTIMER_STEP].number--; |
| | TM_END(mjTIMER_STEP); |
| | } |
| |
|