| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| |
|
| | #include "engine/engine_core_constraint.h" |
| |
|
| | #include <stdio.h> |
| | #include <stddef.h> |
| |
|
| | #include <mujoco/mjdata.h> |
| | #include <mujoco/mjmacro.h> |
| | #include <mujoco/mjmodel.h> |
| | #include <mujoco/mjsan.h> |
| | #include <mujoco/mjxmacro.h> |
| | #include "engine/engine_core_smooth.h" |
| | #include "engine/engine_io.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" |
| | #include "engine/engine_util_spatial.h" |
| |
|
| | #ifdef MEMORY_SANITIZER |
| | #include <sanitizer/msan_interface.h> |
| | #endif |
| |
|
| | #ifdef mjUSEPLATFORMSIMD |
| | #if defined(__AVX__) && !defined(mjUSESINGLE) |
| | #define mjUSEAVX |
| | #endif |
| | #endif |
| |
|
| |
|
| | |
| |
|
| |
|
| |
|
| | |
| | static int arenaAllocEfc(const mjModel* m, mjData* d) { |
| | #undef MJ_M |
| | #define MJ_M(n) m->n |
| | #undef MJ_D |
| | #define MJ_D(n) d->n |
| |
|
| | |
| | d->parena = d->ncon * sizeof(mjContact); |
| |
|
| | |
| | #ifdef ADDRESS_SANITIZER |
| | ASAN_POISON_MEMORY_REGION( |
| | (char*)d->arena + d->parena, d->narena - d->pstack - d->parena); |
| | #endif |
| |
|
| | #define X(type, name, nr, nc) \ |
| | d->name = mj_arenaAllocByte(d, sizeof(type) * (nr) * (nc), _Alignof(type)); \ |
| | if (!d->name) { \ |
| | mj_warning(d, mjWARN_CNSTRFULL, d->narena); \ |
| | mj_clearEfc(d); \ |
| | d->parena = d->ncon * sizeof(mjContact); \ |
| | return 0; \ |
| | } |
| |
|
| | MJDATA_ARENA_POINTERS_SOLVER |
| | #undef X |
| |
|
| | #undef MJ_M |
| | #define MJ_M(n) n |
| | #undef MJ_D |
| | #define MJ_D(n) n |
| |
|
| | return 1; |
| | } |
| |
|
| |
|
| |
|
| | |
| | int mj_isPyramidal(const mjModel* m) { |
| | if (m->opt.cone == mjCONE_PYRAMIDAL) { |
| | return 1; |
| | } else { |
| | return 0; |
| | } |
| | } |
| |
|
| |
|
| |
|
| | |
| | int mj_isSparse(const mjModel* m) { |
| | if (m->opt.jacobian == mjJAC_SPARSE || |
| | (m->opt.jacobian == mjJAC_AUTO && m->nv >= 60)) { |
| | return 1; |
| | } else { |
| | return 0; |
| | } |
| | } |
| |
|
| |
|
| |
|
| | |
| | int mj_isDual(const mjModel* m) { |
| | if (m->opt.solver == mjSOL_PGS || m->opt.noslip_iterations > 0) { |
| | return 1; |
| | } else { |
| | return 0; |
| | } |
| | } |
| |
|
| |
|
| |
|
| | |
| | void mj_assignFriction(const mjModel* m, mjtNum* target, const mjtNum* source) { |
| | if (mjENABLED(mjENBL_OVERRIDE)) { |
| | for (int i=0; i < 5; i++) { |
| | target[i] = mju_max(mjMINMU, m->opt.o_friction[i]); |
| | } |
| | } else { |
| | for (int i=0; i < 5; i++) { |
| | target[i] = mju_max(mjMINMU, source[i]); |
| | } |
| | } |
| | } |
| |
|
| |
|
| |
|
| | |
| | void mj_assignRef(const mjModel* m, mjtNum* target, const mjtNum* source) { |
| | if (mjENABLED(mjENBL_OVERRIDE)) { |
| | mju_copy(target, m->opt.o_solref, mjNREF); |
| | } else { |
| | mju_copy(target, source, mjNREF); |
| | } |
| | } |
| |
|
| |
|
| |
|
| | |
| | void mj_assignImp(const mjModel* m, mjtNum* target, const mjtNum* source) { |
| | if (mjENABLED(mjENBL_OVERRIDE)) { |
| | mju_copy(target, m->opt.o_solimp, mjNIMP); |
| | } else { |
| | mju_copy(target, source, mjNIMP); |
| | } |
| | } |
| |
|
| |
|
| |
|
| | |
| | mjtNum mj_assignMargin(const mjModel* m, mjtNum source) { |
| | if (mjENABLED(mjENBL_OVERRIDE)) { |
| | return m->opt.o_margin; |
| | } else { |
| | return source; |
| | } |
| | } |
| |
|
| |
|
| |
|
| | |
| | |
| | static int mj_elemBodyWeight(const mjModel* m, const mjData* d, int f, int e, int v, |
| | const mjtNum point[3], int* body, mjtNum* weight) { |
| | |
| | int dim = m->flex_dim[f]; |
| | const int* edata = m->flex_elem + m->flex_elemdataadr[f] + e*(dim+1); |
| | const mjtNum* vert = d->flexvert_xpos + 3*m->flex_vertadr[f]; |
| |
|
| | |
| | |
| | int vid = -1; |
| | for (int i=0; i <= dim; i++) { |
| | mjtNum dist = mju_dist3(point, vert+3*edata[i]); |
| | weight[i] = 1.0/(mju_max(mjMINVAL, dist)); |
| | body[i] = m->flex_vertadr[f] + edata[i]; |
| |
|
| | |
| | if (edata[i] == v) { |
| | vid = i; |
| | } |
| | } |
| |
|
| | |
| | if (vid >= 0) { |
| | while (vid < dim) { |
| | weight[vid] = weight[vid+1]; |
| | body[vid] = body[vid+1]; |
| | vid++; |
| | } |
| | dim--; |
| | } |
| |
|
| | |
| | mju_normalize(weight, dim+1); |
| | return dim+1; |
| | } |
| |
|
| |
|
| |
|
| | |
| | static int mj_vertBodyWeight(const mjModel* m, const mjData* d, int f, int v, |
| | const mjtNum point[3], int* body, mjtNum* weight, mjtNum bw) { |
| | mjtNum* coord = m->flex_vert0 + 3*v; |
| | int nstart = m->flex_nodeadr[f]; |
| | int nend = m->flex_nodeadr[f] + m->flex_nodenum[f]; |
| | int nb = 0; |
| |
|
| | for (int i = nstart; i < nend; i++) { |
| | mjtNum w = ((i-nstart)&1 ? coord[2] : 1-coord[2]) * |
| | ((i-nstart)&2 ? coord[1] : 1-coord[1]) * |
| | ((i-nstart)&4 ? coord[0] : 1-coord[0]); |
| | if (w < 1e-5) { |
| | continue; |
| | } |
| | if (weight) weight[nb] = w * bw; |
| | body[nb++] = m->flex_nodebodyid[i]; |
| | } |
| |
|
| | return nb; |
| | } |
| |
|
| |
|
| |
|
| | |
| | int mj_addContact(const mjModel* m, mjData* d, const mjContact* con) { |
| | |
| | if (m->nconmax != -1 && d->ncon >= m->nconmax) { |
| | mj_warning(d, mjWARN_CONTACTFULL, d->ncon); |
| | return 1; |
| | } |
| |
|
| | |
| | d->parena = d->ncon * sizeof(mjContact); |
| | #ifdef ADDRESS_SANITIZER |
| | ASAN_POISON_MEMORY_REGION( |
| | (char*)d->arena + d->parena, d->narena - d->pstack - d->parena); |
| | #endif |
| | mj_clearEfc(d); |
| |
|
| | |
| | mjContact* dst = mj_arenaAllocByte(d, sizeof(mjContact), _Alignof(mjContact)); |
| | if (!dst) { |
| | mj_warning(d, mjWARN_CONTACTFULL, d->ncon); |
| | return 1; |
| | } |
| | *dst = *con; |
| |
|
| | |
| | d->ncon++; |
| | return 0; |
| | } |
| |
|
| |
|
| |
|
| | |
| | static void mj_addConstraint(const mjModel* m, mjData* d, |
| | const mjtNum* jac, const mjtNum* pos, |
| | const mjtNum* margin, mjtNum frictionloss, |
| | int size, int type, int id, int NV, const int* chain) { |
| | int empty, nv = m->nv, nefc = d->nefc; |
| | int *nnz = d->efc_J_rownnz, *adr = d->efc_J_rowadr, *ind = d->efc_J_colind; |
| | mjtNum *J = d->efc_J; |
| |
|
| | |
| | if (type == mjCNSTR_CONTACT_FRICTIONLESS || |
| | type == mjCNSTR_CONTACT_PYRAMIDAL || |
| | type == mjCNSTR_CONTACT_ELLIPTIC) { |
| | empty = 0; |
| | } else { |
| | empty = 1; |
| | } |
| |
|
| | |
| | if (!mj_isSparse(m)) { |
| | |
| | if (empty) { |
| | for (int i=0; i < size*nv; i++) { |
| | if (jac[i]) { |
| | empty = 0; |
| | break; |
| | } |
| | } |
| | } |
| |
|
| | |
| | if (!empty) { |
| | mju_copy(J + nefc*nv, jac, size*nv); |
| | } |
| | } |
| |
|
| | |
| | else { |
| | |
| | NV = mjMAX(0, NV); |
| |
|
| | if (NV) { |
| | empty = 0; |
| | } else if (empty) { |
| | |
| | return; |
| | } |
| |
|
| | |
| | if (NV && !chain) { |
| | mjERROR("called with dense arguments"); |
| | } |
| |
|
| | |
| | for (int i=0; i < size; i++) { |
| | |
| | adr[nefc+i] = (nefc+i ? adr[nefc+i-1]+nnz[nefc+i-1] : 0); |
| |
|
| | |
| | nnz[nefc+i] = NV; |
| |
|
| | |
| | if (NV) { |
| | mju_copyInt(ind + adr[nefc+i], chain, NV); |
| | mju_copy(J + adr[nefc+i], jac + i*NV, NV); |
| | } |
| | } |
| | } |
| |
|
| | |
| | if (empty) { |
| | return; |
| | } |
| |
|
| | |
| | for (int i=0; i < size; i++) { |
| | d->efc_pos[nefc+i] = (pos ? pos[i] : 0); |
| | d->efc_margin[nefc+i] = (margin ? margin[i] : 0); |
| | d->efc_frictionloss[nefc+i] = frictionloss; |
| | d->efc_type[nefc+i] = type; |
| | d->efc_id[nefc+i] = id; |
| | } |
| |
|
| | |
| | d->nefc += size; |
| | if (type == mjCNSTR_EQUALITY) { |
| | d->ne += size; |
| | } else if (type == mjCNSTR_FRICTION_DOF || type == mjCNSTR_FRICTION_TENDON) { |
| | d->nf += size; |
| | } else if (type == mjCNSTR_LIMIT_JOINT || type == mjCNSTR_LIMIT_TENDON) { |
| | d->nl += size; |
| | } |
| | } |
| |
|
| |
|
| |
|
| | |
| | void mj_mulJacVec(const mjModel* m, const mjData* d, mjtNum* res, const mjtNum* vec) { |
| | |
| | if (!d->nefc) { |
| | return; |
| | } |
| |
|
| | |
| | if (mj_isSparse(m)) |
| | mju_mulMatVecSparse(res, d->efc_J, vec, d->nefc, |
| | d->efc_J_rownnz, d->efc_J_rowadr, |
| | d->efc_J_colind, d->efc_J_rowsuper); |
| |
|
| | |
| | else { |
| | mju_mulMatVec(res, d->efc_J, vec, d->nefc, m->nv); |
| | } |
| | } |
| |
|
| |
|
| |
|
| | |
| | void mj_mulJacTVec(const mjModel* m, const mjData* d, mjtNum* res, const mjtNum* vec) { |
| | |
| | if (!d->nefc) { |
| | return; |
| | } |
| |
|
| | |
| | if (mj_isSparse(m)) |
| | mju_mulMatVecSparse(res, d->efc_JT, vec, m->nv, |
| | d->efc_JT_rownnz, d->efc_JT_rowadr, |
| | d->efc_JT_colind, d->efc_JT_rowsuper); |
| |
|
| | |
| | else { |
| | mju_mulMatTVec(res, d->efc_J, vec, d->nefc, m->nv); |
| | } |
| | } |
| |
|
| |
|
| |
|
| | |
| |
|
| | |
| | void mj_instantiateEquality(const mjModel* m, mjData* d) { |
| | int issparse = mj_isSparse(m), nv = m->nv; |
| | int id[2], size, NV, NV2, *chain = NULL, *chain2 = NULL, *buf_ind = NULL; |
| | int flex_edgeadr, flex_edgenum; |
| | mjtNum cpos[6], pos[2][3], ref[2], dif, deriv; |
| | mjtNum quat[4], quat1[4], quat2[4], quat3[4], axis[3]; |
| | mjtNum *jac[2], *jacdif, *data, *sparse_buf = NULL; |
| |
|
| | |
| | if (mjDISABLED(mjDSBL_EQUALITY) || m->nemax == 0) { |
| | return; |
| | } |
| |
|
| | mj_markStack(d); |
| |
|
| | |
| | jac[0] = mjSTACKALLOC(d, 6*nv, mjtNum); |
| | jac[1] = mjSTACKALLOC(d, 6*nv, mjtNum); |
| | jacdif = mjSTACKALLOC(d, 6*nv, mjtNum); |
| | if (issparse) { |
| | chain = mjSTACKALLOC(d, nv, int); |
| | chain2 = mjSTACKALLOC(d, nv, int); |
| | buf_ind = mjSTACKALLOC(d, nv, int); |
| | sparse_buf = mjSTACKALLOC(d, nv, mjtNum); |
| | } |
| |
|
| | |
| | for (int i=0; i < m->neq; i++) { |
| | if (!d->eq_active[i]) { |
| | continue; |
| | } |
| |
|
| | |
| | data = m->eq_data + mjNEQDATA*i; |
| | id[0] = m->eq_obj1id[i]; |
| | id[1] = m->eq_obj2id[i]; |
| | size = 0; |
| | NV = 0; |
| | NV2 = 0; |
| | int body_id[2]; |
| |
|
| | |
| | switch ((mjtEq) m->eq_type[i]) { |
| | case mjEQ_CONNECT: |
| | |
| | if (m->eq_objtype[i] == mjOBJ_BODY) { |
| | for (int j=0; j < 2; j++) { |
| | mju_mulMatVec3(pos[j], d->xmat + 9*id[j], data + 3*j); |
| | mju_addTo3(pos[j], d->xpos + 3*id[j]); |
| | body_id[j] = id[j]; |
| | } |
| | } |
| |
|
| | |
| | else { |
| | for (int j=0; j < 2; j++) { |
| | mju_copy3(pos[j], d->site_xpos + 3*id[j]); |
| | body_id[j] = m->site_bodyid[id[j]]; |
| | } |
| | } |
| |
|
| | |
| | mju_sub3(cpos, pos[0], pos[1]); |
| |
|
| | |
| | NV = mj_jacDifPair(m, d, chain, body_id[1], body_id[0], pos[1], pos[0], |
| | jac[1], jac[0], jacdif, NULL, NULL, NULL); |
| |
|
| | |
| | mju_copy(jac[0], jacdif, 3*NV); |
| |
|
| | size = 3; |
| | break; |
| |
|
| | case mjEQ_WELD: |
| | |
| | if (m->eq_objtype[i] == mjOBJ_BODY) { |
| | for (int j=0; j < 2; j++) { |
| | mjtNum* anchor = data + 3*(1-j); |
| | mju_mulMatVec3(pos[j], d->xmat + 9*id[j], anchor); |
| | mju_addTo3(pos[j], d->xpos + 3*id[j]); |
| | body_id[j] = id[j]; |
| | } |
| | } |
| |
|
| | |
| | else { |
| | for (int j=0; j < 2; j++) { |
| | mju_copy3(pos[j], d->site_xpos + 3*id[j]); |
| | body_id[j] = m->site_bodyid[id[j]]; |
| | } |
| | } |
| |
|
| | |
| | mju_sub3(cpos, pos[0], pos[1]); |
| |
|
| | |
| | mjtNum torquescale = data[10]; |
| |
|
| | |
| | NV = mj_jacDifPair(m, d, chain, body_id[1], body_id[0], pos[1], pos[0], |
| | jac[1], jac[0], jacdif, |
| | jac[1]+3*nv, jac[0]+3*nv, jacdif+3*nv); |
| |
|
| | |
| | mju_copy(jac[0], jacdif, 3*NV); |
| | mju_copy(jac[0]+3*NV, jacdif+3*nv, 3*NV); |
| |
|
| | |
| | if (m->eq_objtype[i] == mjOBJ_BODY) { |
| | |
| | mjtNum* relpose = data+6; |
| | mju_mulQuat(quat, d->xquat+4*id[0], relpose); |
| | mju_negQuat(quat1, d->xquat+4*id[1]); |
| | } |
| |
|
| | |
| | else { |
| | mjtNum quat_site1[4]; |
| | mju_mulQuat(quat, d->xquat+4*body_id[0], m->site_quat+4*id[0]); |
| | mju_mulQuat(quat_site1, d->xquat+4*body_id[1], m->site_quat+4*id[1]); |
| | mju_negQuat(quat1, quat_site1); |
| | } |
| |
|
| | mju_mulQuat(quat2, quat1, quat); |
| | mju_scl3(cpos+3, quat2+1, torquescale); |
| |
|
| | |
| | for (int j=0; j < NV; j++) { |
| | |
| | axis[0] = jac[0][3*NV+j]; |
| | axis[1] = jac[0][4*NV+j]; |
| | axis[2] = jac[0][5*NV+j]; |
| |
|
| | |
| | mju_mulQuatAxis(quat2, quat1, axis); |
| | mju_mulQuat(quat3, quat2, quat); |
| |
|
| | |
| | jac[0][3*NV+j] = 0.5*quat3[1]; |
| | jac[0][4*NV+j] = 0.5*quat3[2]; |
| | jac[0][5*NV+j] = 0.5*quat3[3]; |
| | } |
| |
|
| | |
| | mju_scl(jac[0]+3*NV, jac[0]+3*NV, torquescale, 3*NV); |
| |
|
| | size = 6; |
| | break; |
| |
|
| | case mjEQ_JOINT: |
| | case mjEQ_TENDON: |
| | |
| | for (int j=0; j < 1+(id[1] >= 0); j++) { |
| | if (m->eq_type[i] == mjEQ_JOINT) { |
| | pos[j][0] = d->qpos[m->jnt_qposadr[id[j]]]; |
| | ref[j] = m->qpos0[m->jnt_qposadr[id[j]]]; |
| |
|
| | |
| | if (issparse) { |
| | |
| | if (j == 0) { |
| | NV = 1; |
| | chain[0] = m->jnt_dofadr[id[j]]; |
| | jac[j][0] = 1; |
| | } else { |
| | NV2 = 1; |
| | chain2[0] = m->jnt_dofadr[id[j]]; |
| | jac[j][0] = 1; |
| | } |
| | } else { |
| | mju_zero(jac[j], nv); |
| | jac[j][m->jnt_dofadr[id[j]]] = 1; |
| | } |
| | } else { |
| | pos[j][0] = d->ten_length[id[j]]; |
| | ref[j] = m->tendon_length0[id[j]]; |
| |
|
| | |
| | if (d->tendon_efcadr[id[j]] == -1) { |
| | d->tendon_efcadr[id[j]] = i; |
| | } |
| |
|
| | |
| | if (issparse) { |
| | |
| | if (j == 0) { |
| | NV = d->ten_J_rownnz[id[j]]; |
| | mju_copyInt(chain, d->ten_J_colind+d->ten_J_rowadr[id[j]], NV); |
| | mju_copy(jac[j], d->ten_J+d->ten_J_rowadr[id[j]], NV); |
| | } else { |
| | NV2 = d->ten_J_rownnz[id[j]]; |
| | mju_copyInt(chain2, d->ten_J_colind+d->ten_J_rowadr[id[j]], NV2); |
| | mju_copy(jac[j], d->ten_J+d->ten_J_rowadr[id[j]], NV2); |
| | } |
| | } else { |
| | mju_copy(jac[j], d->ten_J+id[j]*nv, nv); |
| | } |
| | } |
| | } |
| |
|
| | |
| | if (id[1] >= 0) { |
| | |
| | dif = pos[1][0] - ref[1]; |
| | cpos[0] = pos[0][0] - ref[0] - data[0] - |
| | (data[1]*dif + data[2]*dif*dif + data[3]*dif*dif*dif + data[4]*dif*dif*dif*dif); |
| |
|
| | |
| | deriv = data[1] + 2*data[2]*dif + 3*data[3]*dif*dif + 4*data[4]*dif*dif*dif; |
| |
|
| | |
| | if (issparse) { |
| | NV = mju_combineSparse(jac[0], jac[1], 1, -deriv, NV, NV2, chain, |
| | chain2, sparse_buf, buf_ind); |
| | } else { |
| | mju_addToScl(jac[0], jac[1], -deriv, nv); |
| | } |
| | } |
| |
|
| | |
| | else { |
| | |
| | cpos[0] = pos[0][0] - ref[0] - data[0]; |
| |
|
| | |
| | } |
| |
|
| | size = 1; |
| | break; |
| |
|
| | case mjEQ_FLEX: |
| | flex_edgeadr = m->flex_edgeadr[id[0]]; |
| | flex_edgenum = m->flex_edgenum[id[0]]; |
| | |
| | for (int e=flex_edgeadr; e < flex_edgeadr+flex_edgenum; e++) { |
| | |
| | if (m->flexedge_rigid[e]) { |
| | continue; |
| | } |
| |
|
| | |
| | cpos[0] = d->flexedge_length[e] - m->flexedge_length0[e]; |
| |
|
| | |
| | if (issparse) { |
| | mj_addConstraint(m, d, d->flexedge_J+d->flexedge_J_rowadr[e], cpos, 0, 0, |
| | 1, mjCNSTR_EQUALITY, i, |
| | d->flexedge_J_rownnz[e], |
| | d->flexedge_J_colind+d->flexedge_J_rowadr[e]); |
| | } else { |
| | mj_addConstraint(m, d, d->flexedge_J+e*nv, cpos, 0, 0, |
| | 1, mjCNSTR_EQUALITY, i, |
| | 0, NULL); |
| | } |
| | } |
| | break; |
| |
|
| | default: |
| | mjERROR("invalid equality constraint type %d", m->eq_type[i]); |
| | } |
| |
|
| | |
| | if (size) { |
| | mj_addConstraint(m, d, jac[0], cpos, 0, 0, |
| | size, mjCNSTR_EQUALITY, i, |
| | issparse ? NV : 0, |
| | issparse ? chain : NULL); |
| | } |
| | } |
| |
|
| | mj_freeStack(d); |
| | } |
| |
|
| |
|
| |
|
| | |
| | void mj_instantiateFriction(const mjModel* m, mjData* d) { |
| | int nv = m->nv, issparse = mj_isSparse(m); |
| | mjtNum* jac; |
| |
|
| | |
| | if (mjDISABLED(mjDSBL_FRICTIONLOSS)) { |
| | return; |
| | } |
| |
|
| | mj_markStack(d); |
| |
|
| | |
| | jac = mjSTACKALLOC(d, nv, mjtNum); |
| |
|
| | |
| | for (int i=0; i < nv; i++) { |
| | if (m->dof_frictionloss[i] > 0) { |
| | |
| | if (issparse) { |
| | jac[0] = 1; |
| | } else { |
| | mju_zero(jac, nv); |
| | jac[i] = 1; |
| | } |
| |
|
| | |
| | mj_addConstraint(m, d, jac, 0, 0, m->dof_frictionloss[i], |
| | 1, mjCNSTR_FRICTION_DOF, i, |
| | issparse ? 1 : 0, |
| | issparse ? &i : NULL); |
| | } |
| | } |
| |
|
| | |
| | for (int i=0; i < m->ntendon; i++) { |
| | if (m->tendon_frictionloss[i] > 0) { |
| | int efcadr = d->nefc; |
| | |
| | mj_addConstraint(m, d, d->ten_J + (issparse ? d->ten_J_rowadr[i] : i*nv), |
| | 0, 0, m->tendon_frictionloss[i], |
| | 1, mjCNSTR_FRICTION_TENDON, i, |
| | issparse ? d->ten_J_rownnz[i] : 0, |
| | issparse ? d->ten_J_colind+d->ten_J_rowadr[i] : NULL); |
| | |
| | if (d->tendon_efcadr[i] == -1) { |
| | d->tendon_efcadr[i] = efcadr; |
| | } |
| | } |
| | } |
| |
|
| | mj_freeStack(d); |
| | } |
| |
|
| |
|
| |
|
| | |
| | void mj_instantiateLimit(const mjModel* m, mjData* d) { |
| | int side, nv = m->nv, issparse = mj_isSparse(m); |
| | mjtNum margin, value, dist, angleAxis[3]; |
| | mjtNum *jac; |
| |
|
| | |
| | if (mjDISABLED(mjDSBL_LIMIT)) { |
| | return; |
| | } |
| |
|
| | mj_markStack(d); |
| |
|
| | |
| | jac = mjSTACKALLOC(d, nv, mjtNum); |
| |
|
| | |
| | for (int i=0; i < m->njnt; i++) { |
| | if (m->jnt_limited[i]) { |
| | |
| | margin = m->jnt_margin[i]; |
| |
|
| | |
| | if (m->jnt_type[i] == mjJNT_SLIDE || m->jnt_type[i] == mjJNT_HINGE) { |
| | |
| | value = d->qpos[m->jnt_qposadr[i]]; |
| |
|
| | |
| | for (side=-1; side <= 1; side+=2) { |
| | |
| | dist = side * (m->jnt_range[2*i+(side+1)/2] - value); |
| |
|
| | |
| | if (dist < margin) { |
| | |
| | if (issparse) { |
| | jac[0] = -(mjtNum)side; |
| | } else { |
| | mju_zero(jac, nv); |
| | jac[m->jnt_dofadr[i]] = -(mjtNum)side; |
| | } |
| |
|
| | |
| | mj_addConstraint(m, d, jac, &dist, &margin, 0, |
| | 1, mjCNSTR_LIMIT_JOINT, i, |
| | issparse ? 1 : 0, |
| | issparse ? m->jnt_dofadr+i : NULL); |
| | } |
| | } |
| | } |
| |
|
| | |
| | else if (m->jnt_type[i] == mjJNT_BALL) { |
| | |
| | int adr = m->jnt_qposadr[i]; |
| | mjtNum quat[4] = {d->qpos[adr], d->qpos[adr+1], d->qpos[adr+2], d->qpos[adr+3]}; |
| | mju_normalize4(quat); |
| | mju_quat2Vel(angleAxis, quat, 1); |
| |
|
| | |
| | value = mju_normalize3(angleAxis); |
| |
|
| | |
| | dist = mju_max(m->jnt_range[2*i], m->jnt_range[2*i+1]) - value; |
| |
|
| | |
| | if (dist < margin) { |
| | |
| | if (issparse) { |
| | |
| | int chain[3] = { |
| | m->jnt_dofadr[i], |
| | m->jnt_dofadr[i] + 1, |
| | m->jnt_dofadr[i] + 2 |
| | }; |
| |
|
| | |
| | mju_scl3(jac, angleAxis, -1); |
| |
|
| | |
| | mj_addConstraint(m, d, jac, &dist, &margin, 0, |
| | 1, mjCNSTR_LIMIT_JOINT, i, 3, chain); |
| | } |
| |
|
| | |
| | else { |
| | |
| | mju_zero(jac, nv); |
| | mju_scl3(jac + m->jnt_dofadr[i], angleAxis, -1); |
| |
|
| | |
| | mj_addConstraint(m, d, jac, &dist, &margin, 0, |
| | 1, mjCNSTR_LIMIT_JOINT, i, 0, 0); |
| | } |
| | } |
| | } |
| | } |
| | } |
| |
|
| | |
| | for (int i=0; i < m->ntendon; i++) { |
| | if (m->tendon_limited[i]) { |
| | |
| | value = d->ten_length[i]; |
| | margin = m->tendon_margin[i]; |
| |
|
| | |
| | for (side=-1; side <= 1; side+=2) { |
| | |
| | dist = side * (m->tendon_range[2*i+(side+1)/2] - value); |
| |
|
| | |
| | if (dist < margin) { |
| | |
| | if (issparse) { |
| | mju_scl(jac, d->ten_J+d->ten_J_rowadr[i], -side, d->ten_J_rownnz[i]); |
| | } else { |
| | mju_scl(jac, d->ten_J+i*nv, -side, nv); |
| | } |
| |
|
| | |
| | int efcadr = d->nefc; |
| | mj_addConstraint(m, d, jac, &dist, &margin, 0, |
| | 1, mjCNSTR_LIMIT_TENDON, i, |
| | issparse ? d->ten_J_rownnz[i] : 0, |
| | issparse ? d->ten_J_colind+d->ten_J_rowadr[i] : NULL); |
| | |
| | if (d->tendon_efcadr[i] == -1) { |
| | d->tendon_efcadr[i] = efcadr; |
| | } |
| | } |
| | } |
| | } |
| | } |
| |
|
| | mj_freeStack(d); |
| | } |
| |
|
| |
|
| |
|
| | |
| | void mj_instantiateContact(const mjModel* m, mjData* d) { |
| | int ispyramid = mj_isPyramidal(m), issparse = mj_isSparse(m), ncon = d->ncon; |
| | int dim, NV, nv = m->nv, *chain = NULL; |
| | mjContact* con; |
| | mjtNum cpos[6], cmargin[6], *jac, *jacdif, *jacdifp, *jacdifr, *jac1p, *jac2p, *jac1r, *jac2r; |
| |
|
| | if (mjDISABLED(mjDSBL_CONTACT) || ncon == 0 || nv == 0) { |
| | return; |
| | } |
| |
|
| | mj_markStack(d); |
| |
|
| | |
| | jac = mjSTACKALLOC(d, 6*nv, mjtNum); |
| | jacdif = mjSTACKALLOC(d, 6*nv, mjtNum); |
| | jacdifp = jacdif; |
| | jacdifr = jacdif + 3*nv; |
| | jac1p = mjSTACKALLOC(d, 3*nv, mjtNum); |
| | jac2p = mjSTACKALLOC(d, 3*nv, mjtNum); |
| | jac1r = mjSTACKALLOC(d, 3*nv, mjtNum); |
| | jac2r = mjSTACKALLOC(d, 3*nv, mjtNum); |
| | if (issparse) { |
| | chain = mjSTACKALLOC(d, nv, int); |
| | } |
| |
|
| | |
| | for (int i=0; i < ncon; i++) { |
| | if (!d->contact[i].exclude) { |
| | |
| | con = d->contact + i; |
| | dim = con->dim; |
| | con->efc_address = d->nefc; |
| |
|
| | |
| | if ((con->geom[0] >= 0 || (con->vert[0] >= 0 && m->flex_interp[con->flex[0]] == 0)) && |
| | (con->geom[1] >= 0 || (con->vert[1] >= 0 && m->flex_interp[con->flex[1]] == 0))) { |
| | |
| | int bid[2]; |
| | for (int side=0; side < 2; side++) { |
| | bid[side] = (con->geom[side] >= 0) ? |
| | m->geom_bodyid[con->geom[side]] : |
| | m->flex_vertbodyid[m->flex_vertadr[con->flex[side]] + con->vert[side]]; |
| | } |
| |
|
| | |
| | if (dim > 3) { |
| | NV = mj_jacDifPair(m, d, chain, bid[0], bid[1], con->pos, con->pos, |
| | jac1p, jac2p, jacdifp, jac1r, jac2r, jacdifr); |
| | } else { |
| | NV = mj_jacDifPair(m, d, chain, bid[0], bid[1], con->pos, con->pos, |
| | jac1p, jac2p, jacdifp, NULL, NULL, NULL); |
| | } |
| | } |
| |
|
| | |
| | else { |
| | |
| | int nb = 0; |
| | int bid[64]; |
| | mjtNum bweight[64]; |
| | for (int side=0; side < 2; side++) { |
| | int nw = 0; |
| | int vid[4]; |
| | mjtNum bw[4]; |
| |
|
| | |
| | if (con->geom[side] >= 0) { |
| | bid[nb] = m->geom_bodyid[con->geom[side]]; |
| | bweight[nb] = side ? +1 : -1; |
| | nb++; |
| | } |
| |
|
| | |
| | else if (con->vert[side] >= 0) { |
| | vid[0] = m->flex_vertadr[con->flex[side]] + con->vert[side]; |
| | bw[0] = side ? +1 : -1; |
| | nw = 1; |
| | } |
| |
|
| | |
| | else { |
| | nw = mj_elemBodyWeight(m, d, con->flex[side], con->elem[side], |
| | con->vert[1-side], con->pos, vid, bw); |
| |
|
| | |
| | if (side == 0) { |
| | mju_scl(bw, bw, -1, nw); |
| | } |
| | } |
| |
|
| | |
| | for (int k=0; k < nw; k++) { |
| | if (m->flex_interp[con->flex[side]] == 0) { |
| | bid[nb] = m->flex_vertbodyid[vid[k]]; |
| | bweight[nb] = bw[k]; |
| | nb++; |
| | } else { |
| | nb += mj_vertBodyWeight(m, d, con->flex[side], vid[k], |
| | con->pos, bid+nb, bweight+nb, bw[k]); |
| | } |
| | } |
| | } |
| |
|
| | |
| | NV = mj_jacSum(m, d, chain, nb, bid, bweight, con->pos, jacdif, dim > 3); |
| | } |
| |
|
| | |
| | if (NV == 0) { |
| | con->efc_address = -1; |
| | con->exclude = 3; |
| | continue; |
| | } |
| |
|
| | |
| | mju_mulMatMat(jac, con->frame, jacdifp, dim > 1 ? 3 : 1, 3, NV); |
| | if (dim > 3) { |
| | mju_mulMatMat(jac + 3*NV, con->frame, jacdifr, dim-3, 3, NV); |
| | } |
| |
|
| | |
| | if (dim == 1) { |
| | |
| | mj_addConstraint(m, d, jac, &(con->dist), &(con->includemargin), 0, |
| | 1, mjCNSTR_CONTACT_FRICTIONLESS, i, |
| | issparse ? NV : 0, |
| | issparse ? chain : NULL); |
| | } |
| |
|
| | |
| | else if (ispyramid) { |
| | |
| | cpos[0] = cpos[1] = con->dist; |
| | cmargin[0] = cmargin[1] = con->includemargin; |
| |
|
| | |
| | for (int k=1; k < con->dim; k++) { |
| | |
| | mju_addScl(jacdifp, jac, jac + k*NV, con->friction[k-1], NV); |
| | mju_addScl(jacdifp + NV, jac, jac + k*NV, -con->friction[k-1], NV); |
| |
|
| | |
| | mj_addConstraint(m, d, jacdifp, cpos, cmargin, 0, |
| | 2, mjCNSTR_CONTACT_PYRAMIDAL, i, |
| | issparse ? NV : 0, |
| | issparse ? chain : NULL); |
| | } |
| | } |
| |
|
| | |
| | else { |
| | |
| | mju_zero(cpos, con->dim); |
| | mju_zero(cmargin, con->dim); |
| | cpos[0] = con->dist; |
| | cmargin[0] = con->includemargin; |
| |
|
| | |
| | mj_addConstraint(m, d, jac, cpos, cmargin, 0, |
| | con->dim, mjCNSTR_CONTACT_ELLIPTIC, i, |
| | issparse ? NV : 0, |
| | issparse ? chain : NULL); |
| | } |
| | } |
| | } |
| |
|
| | mj_freeStack(d); |
| | } |
| |
|
| |
|
| |
|
| | |
| |
|
| | |
| | void mj_diagApprox(const mjModel* m, mjData* d) { |
| | int id, dim, b1, b2, f, weldcnt = 0; |
| | int nefc = d->nefc; |
| | mjtNum tran, rot, fri, *dA = d->efc_diagApprox; |
| | mjContact* con = NULL; |
| |
|
| | |
| | for (int i=0; i < nefc; i++) { |
| | |
| | id = d->efc_id[i]; |
| |
|
| | |
| | switch ((mjtConstraint) d->efc_type[i]) { |
| | case mjCNSTR_EQUALITY: |
| | |
| | switch (m->eq_type[id]) { |
| | case mjEQ_CONNECT: |
| | b1 = m->eq_obj1id[id]; |
| | b2 = m->eq_obj2id[id]; |
| |
|
| | |
| | if (m->eq_objtype[id] == mjOBJ_SITE) { |
| | b1 = m->site_bodyid[b1]; |
| | b2 = m->site_bodyid[b2]; |
| | } |
| |
|
| | |
| | dA[i] = m->body_invweight0[2*b1] + m->body_invweight0[2*b2]; |
| | break; |
| |
|
| | case mjEQ_WELD: |
| | b1 = m->eq_obj1id[id]; |
| | b2 = m->eq_obj2id[id]; |
| |
|
| | |
| | if (m->eq_objtype[id] == mjOBJ_SITE) { |
| | b1 = m->site_bodyid[b1]; |
| | b2 = m->site_bodyid[b2]; |
| | } |
| |
|
| | |
| | dA[i] = m->body_invweight0[2*b1 + (weldcnt > 2)] + |
| | m->body_invweight0[2*b2 + (weldcnt > 2)]; |
| | weldcnt = (weldcnt + 1) % 6; |
| | break; |
| |
|
| | case mjEQ_JOINT: |
| | case mjEQ_TENDON: |
| | |
| | dA[i] = (m->eq_type[id] == mjEQ_JOINT ? |
| | m->dof_invweight0[m->jnt_dofadr[m->eq_obj1id[id]]] : |
| | m->tendon_invweight0[m->eq_obj1id[id]]); |
| |
|
| | |
| | if (m->eq_obj2id[id] >= 0) |
| | dA[i] += (m->eq_type[id] == mjEQ_JOINT ? |
| | m->dof_invweight0[m->jnt_dofadr[m->eq_obj2id[id]]] : |
| | m->tendon_invweight0[m->eq_obj2id[id]]); |
| | break; |
| |
|
| | case mjEQ_FLEX: |
| | |
| | f = m->eq_obj1id[id]; |
| | int flex_edgeadr = m->flex_edgeadr[f]; |
| | int flex_edgenum = m->flex_edgenum[f]; |
| | for (int e=flex_edgeadr; e<flex_edgeadr+flex_edgenum; e++) { |
| | if (!m->flexedge_rigid[e]) { |
| | dA[i++] = m->flexedge_invweight0[e]; |
| | } |
| | } |
| |
|
| | |
| | i--; |
| | break; |
| |
|
| | default: |
| | mjERROR("unknown constraint type type %d", d->efc_type[i]); |
| | } |
| | break; |
| |
|
| | case mjCNSTR_FRICTION_DOF: |
| | dA[i] = m->dof_invweight0[id]; |
| | break; |
| |
|
| | case mjCNSTR_LIMIT_JOINT: |
| | dA[i] = m->dof_invweight0[m->jnt_dofadr[id]]; |
| | break; |
| |
|
| | case mjCNSTR_FRICTION_TENDON: |
| | case mjCNSTR_LIMIT_TENDON: |
| | dA[i] = m->tendon_invweight0[id]; |
| | break; |
| |
|
| | case mjCNSTR_CONTACT_FRICTIONLESS: |
| | case mjCNSTR_CONTACT_PYRAMIDAL: |
| | case mjCNSTR_CONTACT_ELLIPTIC: |
| | |
| | con = d->contact + id; |
| | dim = con->dim; |
| |
|
| | |
| | tran = rot = 0; |
| | for (int side=0; side < 2; side++) { |
| | |
| | int nb = 0, bid[32], vid[4], nw = 0; |
| | mjtNum bweight[32], bw[4]; |
| |
|
| | |
| | if (con->geom[side] >= 0) { |
| | bid[0] = m->geom_bodyid[con->geom[side]]; |
| | bweight[0] = 1; |
| | nb = 1; |
| | } |
| |
|
| | |
| | else if (con->vert[side] >= 0) { |
| | vid[0] = m->flex_vertadr[con->flex[side]] + con->vert[side]; |
| | bw[0] = 1; |
| | nw = 1; |
| | } |
| |
|
| | |
| | else { |
| | nw = mj_elemBodyWeight(m, d, con->flex[side], con->elem[side], |
| | con->vert[1-side], con->pos, vid, bw); |
| | } |
| |
|
| | |
| | for (int k=0; k < nw; k++) { |
| | if (m->flex_interp[con->flex[side]] == 0) { |
| | bid[k] = m->flex_vertbodyid[vid[k]]; |
| | bweight[k] = bw[k]; |
| | nb++; |
| | } else { |
| | nb = mj_vertBodyWeight(m, d, con->flex[side], vid[k], |
| | con->pos, bid, bweight, bw[k]); |
| | } |
| | } |
| |
|
| | |
| | for (int k=0; k < nb; k++) { |
| | tran += m->body_invweight0[2*bid[k]] * bweight[k]; |
| | rot += m->body_invweight0[2*bid[k]+1] * bweight[k]; |
| | } |
| | } |
| |
|
| | |
| | if (d->efc_type[i] == mjCNSTR_CONTACT_FRICTIONLESS) { |
| | dA[i] = tran; |
| | } |
| |
|
| | |
| | else if (d->efc_type[i] == mjCNSTR_CONTACT_ELLIPTIC) { |
| | for (int j=0; j < dim; j++) { |
| | dA[i+j] = (j < 3 ? tran : rot); |
| | } |
| |
|
| | |
| | i += (dim-1); |
| | } |
| |
|
| | |
| | else { |
| | for (int j=0; j < dim-1; j++) { |
| | fri = con->friction[j]; |
| | dA[i+2*j] = dA[i+2*j+1] = tran + fri*fri*(j < 2 ? tran : rot); |
| | } |
| |
|
| | |
| | i += (2*dim-3); |
| | } |
| | } |
| | } |
| | } |
| |
|
| |
|
| |
|
| | |
| | static void getsolparam(const mjModel* m, const mjData* d, int i, |
| | mjtNum* solref, mjtNum* solreffriction, mjtNum* solimp) { |
| | |
| | int id = d->efc_id[i]; |
| |
|
| | |
| | mju_zero(solreffriction, mjNREF); |
| |
|
| | |
| | switch ((mjtConstraint) d->efc_type[i]) { |
| | case mjCNSTR_EQUALITY: |
| | mju_copy(solref, m->eq_solref+mjNREF*id, mjNREF); |
| | mju_copy(solimp, m->eq_solimp+mjNIMP*id, mjNIMP); |
| | break; |
| |
|
| | case mjCNSTR_LIMIT_JOINT: |
| | mju_copy(solref, m->jnt_solref+mjNREF*id, mjNREF); |
| | mju_copy(solimp, m->jnt_solimp+mjNIMP*id, mjNIMP); |
| | break; |
| |
|
| | case mjCNSTR_FRICTION_DOF: |
| | mju_copy(solref, m->dof_solref+mjNREF*id, mjNREF); |
| | mju_copy(solimp, m->dof_solimp+mjNIMP*id, mjNIMP); |
| | break; |
| |
|
| | case mjCNSTR_LIMIT_TENDON: |
| | mju_copy(solref, m->tendon_solref_lim+mjNREF*id, mjNREF); |
| | mju_copy(solimp, m->tendon_solimp_lim+mjNIMP*id, mjNIMP); |
| | break; |
| |
|
| | case mjCNSTR_FRICTION_TENDON: |
| | mju_copy(solref, m->tendon_solref_fri+mjNREF*id, mjNREF); |
| | mju_copy(solimp, m->tendon_solimp_fri+mjNIMP*id, mjNIMP); |
| | break; |
| |
|
| | case mjCNSTR_CONTACT_FRICTIONLESS: |
| | case mjCNSTR_CONTACT_PYRAMIDAL: |
| | case mjCNSTR_CONTACT_ELLIPTIC: |
| | mju_copy(solref, d->contact[id].solref, mjNREF); |
| | mju_copy(solreffriction, d->contact[id].solreffriction, mjNREF); |
| | mju_copy(solimp, d->contact[id].solimp, mjNIMP); |
| | } |
| |
|
| | |
| | if ((solref[0] > 0) ^ (solref[1] > 0)) { |
| | mju_warning("mixed solref format, replacing with default"); |
| | mj_defaultSolRefImp(solref, NULL); |
| | } |
| |
|
| | |
| | if (!mjDISABLED(mjDSBL_REFSAFE) && solref[0] > 0) { |
| | solref[0] = mju_max(solref[0], 2*m->opt.timestep); |
| | } |
| |
|
| | |
| | if ((solreffriction[0] > 0) ^ (solreffriction[1] > 0)) { |
| | mju_warning("solreffriction values should have the same sign, replacing with default"); |
| | mju_zero(solreffriction, mjNREF); |
| | } |
| |
|
| | |
| | if (!mjDISABLED(mjDSBL_REFSAFE) && solreffriction[0] > 0) { |
| | solreffriction[0] = mju_max(solreffriction[0], 2*m->opt.timestep); |
| | } |
| |
|
| | |
| | solimp[0] = mju_min(mjMAXIMP, mju_max(mjMINIMP, solimp[0])); |
| | solimp[1] = mju_min(mjMAXIMP, mju_max(mjMINIMP, solimp[1])); |
| | solimp[2] = mju_max(0, solimp[2]); |
| | solimp[3] = mju_min(mjMAXIMP, mju_max(mjMINIMP, solimp[3])); |
| | solimp[4] = mju_max(1, solimp[4]); |
| | } |
| |
|
| |
|
| |
|
| | |
| | static void getposdim(const mjModel* m, const mjData* d, int i, mjtNum* pos, int* dim) { |
| | |
| | int id = d->efc_id[i]; |
| |
|
| | |
| | *dim = 1; |
| | *pos = d->efc_pos[i]; |
| |
|
| | |
| | switch ((mjtConstraint) d->efc_type[i]) { |
| | case mjCNSTR_CONTACT_ELLIPTIC: |
| | *dim = d->contact[id].dim; |
| | break; |
| |
|
| | case mjCNSTR_CONTACT_PYRAMIDAL: |
| | *dim = 2*(d->contact[id].dim-1); |
| | break; |
| |
|
| | case mjCNSTR_EQUALITY: |
| | if (m->eq_type[id] == mjEQ_WELD) { |
| | *dim = 6; |
| | *pos = mju_norm(d->efc_pos+i, 6); |
| | } else if (m->eq_type[id] == mjEQ_CONNECT) { |
| | *dim = 3; |
| | *pos = mju_norm(d->efc_pos+i, 3); |
| | } |
| | break; |
| | default: |
| | |
| | break; |
| | } |
| | } |
| |
|
| |
|
| |
|
| | |
| | |
| | static mjtNum power(mjtNum a, mjtNum b) { |
| | if (b == 1) { |
| | return a; |
| | } else if (b == 2) { |
| | return a*a; |
| | } |
| | return mju_pow(a, b); |
| | } |
| |
|
| |
|
| |
|
| | |
| | static void getimpedance(const mjtNum* solimp, mjtNum pos, mjtNum margin, |
| | mjtNum* imp, mjtNum* impP) { |
| | |
| | if (solimp[0] == solimp[1] || solimp[2] <= mjMINVAL) { |
| | *imp = 0.5*(solimp[0] + solimp[1]); |
| | *impP = 0; |
| | return; |
| | } |
| |
|
| | |
| | mjtNum x = (pos-margin) / solimp[2]; |
| | mjtNum sgn = 1; |
| | if (x < 0) { |
| | x = -x; |
| | sgn = -1; |
| | } |
| |
|
| | |
| | if (x >= 1 || x <= 0) { |
| | *imp = (x >= 1 ? solimp[1] : solimp[0]); |
| | *impP = 0; |
| | return; |
| | } |
| |
|
| | |
| | mjtNum y, yP; |
| | if (solimp[4] == 1) { |
| | y = x; |
| | yP = 1; |
| | } |
| |
|
| | |
| | else if (x <= solimp[3]) { |
| | mjtNum a = 1/power(solimp[3], solimp[4]-1); |
| | y = a*power(x, solimp[4]); |
| | yP = solimp[4] * a*power(x, solimp[4]-1); |
| | } |
| |
|
| | |
| | else { |
| | mjtNum b = 1/power(1-solimp[3], solimp[4]-1); |
| | y = 1-b*power(1-x, solimp[4]); |
| | yP = solimp[4] * b*power(1-x, solimp[4]-1); |
| | } |
| |
|
| | |
| | *imp = solimp[0] + y*(solimp[1]-solimp[0]); |
| | *impP = yP * sgn * (solimp[1]-solimp[0]) / solimp[2]; |
| | } |
| |
|
| |
|
| |
|
| | |
| | void mj_makeImpedance(const mjModel* m, mjData* d) { |
| | int dim, nefc = d->nefc; |
| | mjtNum *R = d->efc_R, *KBIP = d->efc_KBIP; |
| | mjtNum pos, imp, impP, Rpy, solref[mjNREF], solreffriction[mjNREF], solimp[mjNIMP]; |
| |
|
| | |
| | for (int i=0; i < nefc; i++) { |
| | |
| | getsolparam(m, d, i, solref, solreffriction, solimp); |
| |
|
| | |
| | getposdim(m, d, i, &pos, &dim); |
| |
|
| | |
| | getimpedance(solimp, pos, d->efc_margin[i], &imp, &impP); |
| |
|
| | |
| | for (int j=0; j < dim; j++) { |
| | |
| | R[i+j] = mju_max(mjMINVAL, (1-imp)*d->efc_diagApprox[i+j]/imp); |
| |
|
| | |
| | int tp = d->efc_type[i+j]; |
| |
|
| | |
| | int elliptic_friction = (tp == mjCNSTR_CONTACT_ELLIPTIC) && (j > 0); |
| | mjtNum* ref = elliptic_friction && (solreffriction[0] || solreffriction[1]) ? |
| | solreffriction : solref; |
| |
|
| | |
| | if (tp == mjCNSTR_FRICTION_DOF || tp == mjCNSTR_FRICTION_TENDON || elliptic_friction) { |
| | KBIP[4*(i+j)] = 0; |
| | } |
| |
|
| | |
| | else if (ref[0] > 0) |
| | KBIP[4*(i+j)] = 1 / mju_max(mjMINVAL, solimp[1]*solimp[1] * ref[0]*ref[0] * ref[1]*ref[1]); |
| |
|
| | |
| | else { |
| | KBIP[4*(i+j)] = -ref[0] / mju_max(mjMINVAL, solimp[1]*solimp[1]); |
| | } |
| |
|
| | |
| | if (ref[1] > 0) { |
| | KBIP[4*(i+j)+1] = 2 / mju_max(mjMINVAL, solimp[1]*ref[0]); |
| | } |
| |
|
| | |
| | else { |
| | KBIP[4*(i+j)+1] = -ref[1] / mju_max(mjMINVAL, solimp[1]); |
| | } |
| |
|
| | |
| | KBIP[4*(i+j)+2] = imp; |
| | KBIP[4*(i+j)+3] = impP; |
| | } |
| |
|
| | |
| | i += (dim-1); |
| | } |
| |
|
| | |
| | for (int i=d->ne+d->nf; i < nefc; i++) { |
| | if (d->efc_type[i] == mjCNSTR_CONTACT_PYRAMIDAL || |
| | d->efc_type[i] == mjCNSTR_CONTACT_ELLIPTIC) { |
| | |
| | int id = d->efc_id[i]; |
| | dim = d->contact[id].dim; |
| | mjtNum* friction = d->contact[id].friction; |
| |
|
| | |
| | R[i+1] = R[i]/mju_max(mjMINVAL, m->opt.impratio); |
| |
|
| | |
| | d->contact[id].mu = friction[0] * mju_sqrt(R[i+1]/R[i]); |
| |
|
| | |
| | if (d->efc_type[i] == mjCNSTR_CONTACT_ELLIPTIC) { |
| | |
| | for (int j=1; j < dim-1; j++) { |
| | R[i+j+1] = R[i+1]*friction[0]*friction[0]/(friction[j]*friction[j]); |
| | } |
| |
|
| | |
| | i += (dim-1); |
| | } |
| |
|
| | |
| | else { |
| | |
| | |
| | Rpy = 2*d->contact[id].mu*d->contact[id].mu*R[i]; |
| |
|
| | |
| | for (int j=0; j < 2*(dim-1); j++) { |
| | R[i+j] = Rpy; |
| | } |
| |
|
| | |
| | i += 2*(dim-1) - 1; |
| | } |
| | } |
| | } |
| |
|
| | |
| | for (int i=0; i < nefc; i++) { |
| | d->efc_D[i] = 1 / R[i]; |
| | } |
| |
|
| | |
| | for (int i=0; i < nefc; i++) { |
| | d->efc_diagApprox[i] = R[i] * KBIP[4*i+2] / (1-KBIP[4*i+2]); |
| | } |
| | } |
| |
|
| |
|
| |
|
| | |
| |
|
| | |
| | static int mj_jacDifPairCount(const mjModel* m, int* chain, |
| | int b1, int b2, int issparse) { |
| | if (!m->nv) { |
| | return 0; |
| | } |
| |
|
| | if (issparse) { |
| | if (m->body_simple[b1] && m->body_simple[b2]) { |
| | return mj_mergeChainSimple(m, chain, b1, b2); |
| | } |
| | return mj_mergeChain(m, chain, b1, b2); |
| | } |
| |
|
| | return m->nv; |
| | } |
| |
|
| |
|
| |
|
| | |
| | static int mj_jacSumCount(const mjModel* m, mjData* d, int* chain, |
| | int n, const int* body) { |
| | int nv = m->nv, NV; |
| |
|
| | mj_markStack(d); |
| | int* bodychain = mjSTACKALLOC(d, nv, int); |
| | int* tempchain = mjSTACKALLOC(d, nv, int); |
| |
|
| | |
| | NV = mj_bodyChain(m, body[0], chain); |
| |
|
| | |
| | for (int i=1; i < n; i++) { |
| | |
| | int bodyNV = mj_bodyChain(m, body[i], bodychain); |
| | if (!bodyNV) { |
| | continue; |
| | } |
| |
|
| | |
| | NV = mju_addChains(tempchain, nv, NV, bodyNV, chain, bodychain); |
| | if (NV) { |
| | mju_copyInt(chain, tempchain, NV); |
| | } |
| | } |
| |
|
| | mj_freeStack(d); |
| | return NV; |
| | } |
| |
|
| |
|
| |
|
| | |
| | static inline int mj_addConstraintCount(const mjModel* m, int size, int NV) { |
| | |
| | if (!mj_isSparse(m)) { |
| | return m->nv ? size : 0; |
| | } |
| | return mjMAX(0, NV) ? size : 0; |
| | } |
| |
|
| |
|
| |
|
| | |
| | static int mj_ne(const mjModel* m, mjData* d, int* nnz) { |
| | int ne = 0, nnze = 0; |
| | int nv = m->nv, neq = m->neq; |
| | int id[2], size, NV, NV2, *chain = NULL, *chain2 = NULL; |
| | int issparse = (nnz != NULL); |
| | int flex_edgeadr, flex_edgenum; |
| |
|
| | |
| | if (mjDISABLED(mjDSBL_EQUALITY) || m->nemax == 0) { |
| | return 0; |
| | } |
| |
|
| | mj_markStack(d); |
| |
|
| | if (nnz) { |
| | chain = mjSTACKALLOC(d, nv, int); |
| | chain2 = mjSTACKALLOC(d, nv, int); |
| | } |
| |
|
| | |
| | for (int i=0; i < neq; i++) { |
| | if (d->eq_active[i]) { |
| | id[0] = m->eq_obj1id[i]; |
| | id[1] = m->eq_obj2id[i]; |
| | size = 0; |
| | NV = 0; |
| | NV2 = 0; |
| |
|
| | |
| | switch ((mjtEq) m->eq_type[i]) { |
| | case mjEQ_CONNECT: |
| | size = 3; |
| | if (!nnz) { |
| | break; |
| | } |
| |
|
| | |
| | if (m->eq_objtype[i] == mjOBJ_SITE) { |
| | id[0] = m->site_bodyid[id[0]]; |
| | id[1] = m->site_bodyid[id[1]]; |
| | } |
| |
|
| | NV = mj_jacDifPairCount(m, chain, id[1], id[0], issparse); |
| | break; |
| |
|
| | case mjEQ_WELD: |
| | size = 6; |
| | if (!nnz) { |
| | break; |
| | } |
| |
|
| | |
| | if (m->eq_objtype[i] == mjOBJ_SITE) { |
| | id[0] = m->site_bodyid[id[0]]; |
| | id[1] = m->site_bodyid[id[1]]; |
| | } |
| |
|
| | NV = mj_jacDifPairCount(m, chain, id[1], id[0], issparse); |
| | break; |
| |
|
| | case mjEQ_JOINT: |
| | case mjEQ_TENDON: |
| | size = 1; |
| | if (!nnz) { |
| | break; |
| | } |
| |
|
| | for (int j=0; j < 1+(id[1] >= 0); j++) { |
| | if (m->eq_type[i] == mjEQ_JOINT) { |
| | if (!j) { |
| | NV = 1; |
| | chain[0] = m->jnt_dofadr[id[j]]; |
| | } else { |
| | NV2 = 1; |
| | chain2[0] = m->jnt_dofadr[id[j]]; |
| | } |
| | } else { |
| | if (!j) { |
| | NV = d->ten_J_rownnz[id[j]]; |
| | mju_copyInt(chain, d->ten_J_colind+d->ten_J_rowadr[id[j]], NV); |
| | } else { |
| | NV2 = d->ten_J_rownnz[id[j]]; |
| | mju_copyInt(chain2, d->ten_J_colind+d->ten_J_rowadr[id[j]], NV2); |
| | } |
| | } |
| | } |
| |
|
| | if (id[1] >= 0) { |
| | NV = mju_combineSparseCount(NV, NV2, chain, chain2); |
| | } |
| | break; |
| |
|
| | case mjEQ_FLEX: |
| | flex_edgeadr = m->flex_edgeadr[id[0]]; |
| | flex_edgenum = m->flex_edgenum[id[0]]; |
| |
|
| | |
| | size = flex_edgenum; |
| |
|
| | |
| | for (int e=flex_edgeadr; e < flex_edgeadr+flex_edgenum; e++) { |
| | |
| | if (m->flexedge_rigid[e]) { |
| | size--; |
| | continue; |
| | } |
| |
|
| | |
| | if (nnz) { |
| | int b1 = m->flex_vertbodyid[m->flex_vertadr[id[0]] + m->flex_edge[2*e]]; |
| | int b2 = m->flex_vertbodyid[m->flex_vertadr[id[0]] + m->flex_edge[2*e+1]]; |
| | NV += mj_jacDifPairCount(m, chain, b1, b2, issparse); |
| | } |
| | } |
| | break; |
| |
|
| | default: |
| | |
| | mjERROR("unknown constraint type type %d", m->eq_type[i]); |
| | } |
| |
|
| | |
| | ne += mj_addConstraintCount(m, size, NV); |
| | nnze += (m->eq_type[i] == mjEQ_FLEX) ? NV : size*NV; |
| | } |
| | } |
| |
|
| | if (nnz) { |
| | *nnz += nnze; |
| | } |
| |
|
| | mj_freeStack(d); |
| | return ne; |
| | } |
| |
|
| |
|
| |
|
| | |
| | static int mj_nf(const mjModel* m, const mjData* d, int *nnz) { |
| | int nf = 0; |
| | int nv = m->nv, ntendon = m->ntendon; |
| |
|
| | if (mjDISABLED(mjDSBL_FRICTIONLOSS)) { |
| | return 0; |
| | } |
| |
|
| | for (int i=0; i < nv; i++) { |
| | if (m->dof_frictionloss[i] > 0) { |
| | nf += mj_addConstraintCount(m, 1, 1); |
| | if (nnz) *nnz += 1; |
| | } |
| | } |
| |
|
| | for (int i=0; i < ntendon; i++) { |
| | if (m->tendon_frictionloss[i] > 0) { |
| | nf += mj_addConstraintCount(m, 1, d->ten_J_rownnz[i]); |
| | if (nnz) *nnz += d->ten_J_rownnz[i]; |
| | } |
| | } |
| |
|
| | return nf; |
| | } |
| |
|
| |
|
| |
|
| | |
| | static int mj_nl(const mjModel* m, const mjData* d, int *nnz) { |
| | int nl = 0; |
| | int ntendon = m->ntendon; |
| | int side; |
| | mjtNum margin, value, dist; |
| |
|
| | |
| | if (mjDISABLED(mjDSBL_LIMIT)) { |
| | return 0; |
| | } |
| |
|
| |
|
| | for (int i=0; i < m->njnt; i++) { |
| | if (!m->jnt_limited[i]) { |
| | continue; |
| | } |
| |
|
| | margin = m->jnt_margin[i]; |
| |
|
| | |
| | if (m->jnt_type[i] == mjJNT_SLIDE || m->jnt_type[i] == mjJNT_HINGE) { |
| | value = d->qpos[m->jnt_qposadr[i]]; |
| | for (side=-1; side <= 1; side+=2) { |
| | dist = side * (m->jnt_range[2*i+(side+1)/2] - value); |
| | if (dist < margin) { |
| | nl += mj_addConstraintCount(m, 1, 1); |
| | if (nnz) *nnz += 1; |
| | } |
| | } |
| | } |
| | else if (m->jnt_type[i] == mjJNT_BALL) { |
| | mjtNum angleAxis[3]; |
| | int adr = m->jnt_qposadr[i]; |
| | mjtNum quat[4] = {d->qpos[adr], d->qpos[adr+1], d->qpos[adr+2], d->qpos[adr+3]}; |
| | mju_normalize4(quat); |
| | mju_quat2Vel(angleAxis, quat, 1); |
| | value = mju_normalize3(angleAxis); |
| | dist = mju_max(m->jnt_range[2*i], m->jnt_range[2*i+1]) - value; |
| | if (dist < margin) { |
| | nl += mj_addConstraintCount(m, 1, 3); |
| | if (nnz) *nnz += 3; |
| | } |
| | } |
| | } |
| |
|
| | for (int i=0; i < ntendon; i++) { |
| | if (m->tendon_limited[i]) { |
| | value = d->ten_length[i]; |
| | margin = m->tendon_margin[i]; |
| |
|
| | |
| | for (side=-1; side <= 1; side+=2) { |
| | dist = side * (m->tendon_range[2*i+(side+1)/2] - value); |
| | if (dist < margin) { |
| | nl += mj_addConstraintCount(m, 1, d->ten_J_rownnz[i]); |
| | if (nnz) *nnz += d->ten_J_rownnz[i]; |
| | } |
| | } |
| | } |
| | } |
| |
|
| | return nl; |
| | } |
| |
|
| |
|
| |
|
| | |
| | static int mj_nc(const mjModel* m, mjData* d, int* nnz) { |
| | int nnzc = 0, nc = 0; |
| | int ispyramid = mj_isPyramidal(m), ncon = d->ncon; |
| |
|
| | if (mjDISABLED(mjDSBL_CONTACT) || !ncon) { |
| | return 0; |
| | } |
| |
|
| | mj_markStack(d); |
| | int *chain = mjSTACKALLOC(d, m->nv, int); |
| |
|
| | for (int i=0; i < ncon; i++) { |
| | mjContact* con = d->contact + i; |
| |
|
| | |
| | if (con->exclude) { |
| | continue; |
| | } |
| |
|
| | |
| | int NV = 0; |
| | if (nnz) { |
| | |
| | int nb = 0, bid[64]; |
| | for (int side=0; side < 2; side++) { |
| | int nw = 0; |
| | int vid[4]; |
| |
|
| | |
| | if (con->geom[side] >= 0) { |
| | bid[nb++] = m->geom_bodyid[con->geom[side]]; |
| | } |
| |
|
| | |
| | else if (con->vert[side] >= 0) { |
| | vid[nw++] = m->flex_vertadr[con->flex[side]] + con->vert[side]; |
| | } |
| |
|
| | |
| | else { |
| | int f = con->flex[side]; |
| | int fdim = m->flex_dim[f]; |
| | const int* edata = m->flex_elem + m->flex_elemdataadr[f] + con->elem[side]*(fdim+1); |
| | for (int k=0; k <= fdim; k++) { |
| | vid[nw++] = m->flex_vertadr[f] + edata[k]; |
| | } |
| | } |
| |
|
| | |
| | for (int k=0; k < nw; k++) { |
| | if (m->flex_interp[con->flex[side]] == 0) { |
| | bid[nb] = m->flex_vertbodyid[vid[k]]; |
| | nb++; |
| | } else { |
| | nb += mj_vertBodyWeight(m, d, con->flex[side], vid[k], |
| | con->pos, bid+nb, NULL, 0); |
| | } |
| | } |
| | } |
| |
|
| | |
| | NV = mj_jacSumCount(m, d, chain, nb, bid); |
| | if (!NV) { |
| | continue; |
| | } |
| | } |
| |
|
| | |
| | int dim = con->dim; |
| | if (dim == 1) { |
| | nc++; |
| | nnzc += NV; |
| | } else if (ispyramid) { |
| | nc += 2*(dim-1); |
| | nnzc += 2*(dim-1)*NV; |
| | } else { |
| | nc += dim; |
| | nnzc += dim*NV; |
| | } |
| | } |
| |
|
| | if (nnz) { |
| | *nnz += nnzc; |
| | } |
| |
|
| | mj_freeStack(d); |
| | return nc; |
| | } |
| |
|
| |
|
| |
|
| | |
| |
|
| | |
| | void mj_makeConstraint(const mjModel* m, mjData* d) { |
| | |
| | d->ne = d->nf = d->nl = d->nefc = d->nJ = d->nA = 0; |
| |
|
| | |
| | if (mjDISABLED(mjDSBL_CONSTRAINT)) { |
| | return; |
| | } |
| |
|
| | |
| | int *nnz = mj_isSparse(m) ? &(d->nJ) : NULL; |
| | int ne_allocated = mj_ne(m, d, nnz); |
| | int nf_allocated = mj_nf(m, d, nnz); |
| | int nl_allocated = mj_nl(m, d, nnz); |
| | int nefc_allocated = ne_allocated + nf_allocated + nl_allocated + mj_nc(m, d, nnz); |
| | if (!mj_isSparse(m)) { |
| | d->nJ = nefc_allocated * m->nv; |
| | } |
| | d->nefc = nefc_allocated; |
| |
|
| | |
| | if (!arenaAllocEfc(m, d)) { |
| | return; |
| | } |
| |
|
| | |
| | for (int i=0; i < m->ntendon; i++) { |
| | d->tendon_efcadr[i] = -1; |
| | } |
| |
|
| | |
| | |
| | d->nefc = 0; |
| | mj_instantiateEquality(m, d); |
| | mj_instantiateFriction(m, d); |
| | mj_instantiateLimit(m, d); |
| | mj_instantiateContact(m, d); |
| |
|
| | |
| | if (mj_isSparse(m)) { |
| | if (d->ne != ne_allocated) { |
| | mjERROR("ne mis-allocation: found ne=%d but allocated %d", d->ne, ne_allocated); |
| | } |
| |
|
| | if (d->nf != nf_allocated) { |
| | mjERROR("nf mis-allocation: found nf=%d but allocated %d", d->nf, nf_allocated); |
| | } |
| |
|
| | if (d->nl != nl_allocated) { |
| | mjERROR("nl mis-allocation: found nl=%d but allocated %d", d->nl, nl_allocated); |
| | } |
| |
|
| | |
| | if (d->nefc != nefc_allocated) { |
| | mjERROR("nefc mis-allocation: found nefc=%d but allocated %d", d->nefc, nefc_allocated); |
| | } |
| |
|
| | |
| | if (d->nefc > 0) { |
| | int nJ = d->efc_J_rownnz[d->nefc - 1] + d->efc_J_rowadr[d->nefc - 1]; |
| | if (d->nJ != nJ) { |
| | mjERROR("constraint Jacobian mis-allocation: found nJ=%d but allocated %d", nJ, d->nJ); |
| | } |
| | } |
| | } else if (d->nefc > nefc_allocated) { |
| | mjERROR("nefc under-allocation: found nefc=%d but allocated only %d", |
| | d->nefc, nefc_allocated); |
| | } |
| |
|
| | |
| | d->maxuse_con = mjMAX(d->maxuse_con, d->ncon); |
| | d->maxuse_efc = mjMAX(d->maxuse_efc, d->nefc); |
| |
|
| | |
| | if (!d->nefc) { |
| | return; |
| | } |
| |
|
| | |
| | if (mj_isSparse(m)) { |
| | |
| | mju_transposeSparse(d->efc_JT, d->efc_J, d->nefc, m->nv, |
| | d->efc_JT_rownnz, d->efc_JT_rowadr, d->efc_JT_colind, d->efc_JT_rowsuper, |
| | d->efc_J_rownnz, d->efc_J_rowadr, d->efc_J_colind); |
| |
|
| |
|
| | #ifdef mjUSEAVX |
| | |
| | mju_superSparse(d->nefc, d->efc_J_rowsuper, |
| | d->efc_J_rownnz, d->efc_J_rowadr, d->efc_J_colind); |
| | #else |
| | #ifdef MEMORY_SANITIZER |
| | |
| | __msan_allocated_memory(d->efc_J_rowsuper, d->nefc); |
| | #endif |
| | #endif |
| | } |
| |
|
| | |
| | mj_diagApprox(m, d); |
| |
|
| | |
| | mj_makeImpedance(m, d); |
| | } |
| |
|
| |
|
| |
|
| | |
| | void mj_projectConstraint(const mjModel* m, mjData* d) { |
| | int nefc = d->nefc, nv = m->nv; |
| |
|
| | |
| | if (nefc == 0 || !mj_isDual(m)) { |
| | return; |
| | } |
| |
|
| | mj_markStack(d); |
| |
|
| | |
| | mjtNum* sqrtInvD = mjSTACKALLOC(d, nv, mjtNum); |
| | for (int i=0; i < nv; i++) { |
| | int diag = d->M_rowadr[i] + d->M_rownnz[i] - 1; |
| | sqrtInvD[i] = 1 / mju_sqrt(d->qLD[diag]); |
| | } |
| |
|
| | |
| | if (mj_isSparse(m)) { |
| | |
| |
|
| |
|
| | |
| |
|
| | |
| | int* B_rownnz = mjSTACKALLOC(d, nefc, int); |
| | int* B_rowadr = mjSTACKALLOC(d, nefc, int); |
| |
|
| | |
| | int* marker = mjSTACKALLOC(d, nv, int); |
| | for (int i=0; i < nv; i++) { |
| | marker[i] = -1; |
| | } |
| |
|
| | B_rowadr[0] = 0; |
| | for (int r=0; r < nefc; r++) { |
| | int nnz = 0; |
| |
|
| | |
| | int start = d->efc_J_rowadr[r]; |
| | int end = start + d->efc_J_rownnz[r]; |
| | for (int i=end-1; i >= start; i--) { |
| | int j = d->efc_J_colind[i]; |
| |
|
| | |
| | if (marker[j] == r) { |
| | continue; |
| | } |
| |
|
| | |
| | int nnzC = d->M_rownnz[j]; |
| | int adrC = d->M_rowadr[j]; |
| | for (int k=0; k < nnzC; k++) { |
| | int c = d->M_colind[adrC + k]; |
| | if (marker[c] != r) { |
| | marker[c] = r; |
| | nnz++; |
| | } |
| | } |
| | } |
| |
|
| | |
| | B_rownnz[r] = nnz; |
| | if (r < nefc - 1) { |
| | B_rowadr[r+1] = B_rowadr[r] + nnz; |
| | } |
| | } |
| |
|
| | |
| | int nB = B_rowadr[nefc-1] + B_rownnz[nefc-1]; |
| |
|
| |
|
| | |
| |
|
| | |
| | mjtNum* B = mjSTACKALLOC(d, nB, mjtNum); |
| | int* B_colind = mjSTACKALLOC(d, nB, int); |
| |
|
| | for (int r=0; r < nefc; r++) { |
| | |
| | int end = B_rowadr[r] + B_rownnz[r]; |
| | int adrJ = d->efc_J_rowadr[r]; |
| | int remainJ = d->efc_J_rownnz[r]; |
| | int nnzB = 0; |
| |
|
| | |
| | while (1) { |
| | |
| | int prev_src = (remainJ > 0 ? d->efc_J_colind[adrJ + remainJ - 1] : -1); |
| | int prev_dst = (nnzB > 0 ? m->dof_parentid[B_colind[end - nnzB]] : -1); |
| |
|
| | |
| | if (prev_src < 0 && prev_dst < 0) { |
| | break; |
| | } |
| |
|
| | |
| | else if (prev_src >= prev_dst) { |
| | nnzB++; |
| | remainJ--; |
| | B_colind[end - nnzB] = prev_src; |
| | B[end - nnzB] = d->efc_J[adrJ + remainJ]; |
| | } |
| |
|
| | |
| | else { |
| | nnzB++; |
| | B_colind[end - nnzB] = prev_dst; |
| | B[end - nnzB] = 0; |
| | } |
| | } |
| |
|
| | |
| | if (nnzB != B_rownnz[r]) { |
| | mjERROR("pre and post-count of B_rownnz are not equal on row %d", r); |
| | } |
| | } |
| |
|
| |
|
| | |
| |
|
| | |
| | for (int r=0; r < nefc; r++) { |
| | int nnzB = B_rownnz[r]; |
| | int adrB = B_rowadr[r]; |
| |
|
| | |
| | for (int i=adrB + nnzB-1; i >= adrB; i--) { |
| | mjtNum b = B[i]; |
| | if (b == 0) { |
| | continue; |
| | } |
| | int j = B_colind[i]; |
| | int adrC = d->M_rowadr[j]; |
| | mju_addToSclSparseInc(B + adrB, d->qLD + adrC, |
| | nnzB, B_colind + adrB, |
| | d->M_rownnz[j]-1, d->M_colind + adrC, -b); |
| | } |
| |
|
| | |
| | for (int i=adrB; i < adrB + nnzB; i++) { |
| | int j = B_colind[i]; |
| | B[i] *= sqrtInvD[j]; |
| | } |
| | } |
| |
|
| | |
| | int* B_rowsuper = mjSTACKALLOC(d, nefc, int); |
| | mju_superSparse(nefc, B_rowsuper, B_rownnz, B_rowadr, B_colind); |
| |
|
| | |
| | int* BT_rownnz = mjSTACKALLOC(d, nv, int); |
| | int* BT_rowadr = mjSTACKALLOC(d, nv, int); |
| | int* BT_colind = mjSTACKALLOC(d, nB, int); |
| | mjtNum* BT = mjSTACKALLOC(d, nB, mjtNum); |
| | mju_transposeSparse(BT, B, nefc, nv, |
| | BT_rownnz, BT_rowadr, BT_colind, NULL, |
| | B_rownnz, B_rowadr, B_colind); |
| |
|
| | |
| | d->efc_AR_rownnz = mj_arenaAllocByte(d, sizeof(int) * nefc, _Alignof(int)); |
| | d->efc_AR_rowadr = mj_arenaAllocByte(d, sizeof(int) * nefc, _Alignof(int)); |
| | if (!d->efc_AR_rownnz || !d->efc_AR_rowadr) { |
| | mj_warning(d, mjWARN_CNSTRFULL, d->narena); |
| | mj_clearEfc(d); |
| | d->parena = d->ncon * sizeof(mjContact); |
| | mj_freeStack(d); |
| | return; |
| | } |
| |
|
| | |
| | d->nA = mju_sqrMatTDSparseCount(d->efc_AR_rownnz, d->efc_AR_rowadr, nefc, |
| | BT_rownnz, BT_rowadr, BT_colind, |
| | B_rownnz, B_rowadr, B_colind, B_rowsuper, d, 1); |
| |
|
| | |
| | d->efc_AR = mj_arenaAllocByte(d, sizeof(mjtNum) * d->nA, _Alignof(mjtNum)); |
| | d->efc_AR_colind = mj_arenaAllocByte(d, sizeof(int) * d->nA, _Alignof(int)); |
| | if (!d->efc_AR || !d->efc_AR_colind) { |
| | mj_warning(d, mjWARN_CNSTRFULL, d->narena); |
| | mj_clearEfc(d); |
| | d->parena = d->ncon * sizeof(mjContact); |
| | mj_freeStack(d); |
| | return; |
| | } |
| |
|
| | |
| | int* diagind = mjSTACKALLOC(d, nefc, int); |
| | mju_sqrMatTDSparse(d->efc_AR, BT, B, NULL, nv, nefc, |
| | d->efc_AR_rownnz, d->efc_AR_rowadr, d->efc_AR_colind, |
| | BT_rownnz, BT_rowadr, BT_colind, NULL, |
| | B_rownnz, B_rowadr, B_colind, B_rowsuper, d, diagind); |
| |
|
| | |
| | for (int i=0; i < nefc; i++) { |
| | d->efc_AR[diagind[i]] += d->efc_R[i]; |
| | } |
| | } |
| |
|
| | |
| | else { |
| | d->nA = nefc * nefc; |
| |
|
| | |
| | d->efc_AR = mj_arenaAllocByte(d, sizeof(mjtNum) * d->nA, _Alignof(mjtNum)); |
| | if (!d->efc_AR) { |
| | mj_warning(d, mjWARN_CNSTRFULL, d->narena); |
| | mj_clearEfc(d); |
| | d->parena = d->ncon * sizeof(mjContact); |
| | mj_freeStack(d); |
| | return; |
| | } |
| |
|
| | |
| | mjtNum* B = mjSTACKALLOC(d, nefc*nv, mjtNum); |
| | mjtNum* BT = mjSTACKALLOC(d, nv*nefc, mjtNum); |
| |
|
| | |
| | mj_solveM2(m, d, B, d->efc_J, sqrtInvD, nefc); |
| |
|
| | |
| | mju_transpose(BT, B, nefc, nv); |
| |
|
| | |
| | mju_sqrMatTD(d->efc_AR, BT, NULL, nv, nefc); |
| |
|
| | |
| | for (int r=0; r < nefc; r++) { |
| | d->efc_AR[r*(nefc+1)] += d->efc_R[r]; |
| | } |
| | } |
| |
|
| | mj_freeStack(d); |
| | } |
| |
|
| |
|
| |
|
| | |
| | void mj_referenceConstraint(const mjModel* m, mjData* d) { |
| | int nefc = d->nefc; |
| | mjtNum* KBIP = d->efc_KBIP; |
| |
|
| | |
| | mj_mulJacVec(m, d, d->efc_vel, d->qvel); |
| |
|
| | |
| | for (int i=0; i < nefc; i++) { |
| | d->efc_aref[i] = -KBIP[4*i+1]*d->efc_vel[i] |
| | -KBIP[4*i]*KBIP[4*i+2]*(d->efc_pos[i]-d->efc_margin[i]); |
| | } |
| | } |
| |
|
| |
|
| |
|
| | |
| |
|
| | |
| | |
| | void mj_constraintUpdate_impl(int ne, int nf, int nefc, |
| | const mjtNum* D, const mjtNum* R, const mjtNum* floss, |
| | const mjtNum* jar, const int* type, const int* id, |
| | mjContact* contact, int* state, mjtNum* force, mjtNum cost[1], |
| | int flg_coneHessian) { |
| | mjtNum s = 0; |
| |
|
| | |
| | if (!nefc) { |
| | if (cost) { |
| | *cost = 0; |
| | } |
| | return; |
| | } |
| |
|
| | |
| | for (int i=0; i < nefc; i++) { |
| | force[i] = -D[i]*jar[i]; |
| | } |
| |
|
| | |
| | for (int i=0; i < nefc; i++) { |
| | |
| | if (i < ne) { |
| | if (cost) { |
| | s += 0.5*D[i]*jar[i]*jar[i]; |
| | } |
| | state[i] = mjCNSTRSTATE_QUADRATIC; |
| | continue; |
| | } |
| |
|
| | |
| | if (i < ne + nf) { |
| | |
| | if (jar[i] <= -R[i]*floss[i]) { |
| | if (cost) { |
| | s += -0.5*R[i]*floss[i]*floss[i] - floss[i]*jar[i]; |
| | } |
| |
|
| | force[i] = floss[i]; |
| | state[i] = mjCNSTRSTATE_LINEARNEG; |
| | } |
| |
|
| | |
| | else if (jar[i] >= R[i]*floss[i]) { |
| | if (cost) { |
| | s += -0.5*R[i]*floss[i]*floss[i] + floss[i]*jar[i]; |
| | } |
| |
|
| | force[i] = -floss[i]; |
| | state[i] = mjCNSTRSTATE_LINEARPOS; |
| | } |
| |
|
| | |
| | else { |
| | if (cost) { |
| | s += 0.5*D[i]*jar[i]*jar[i]; |
| | } |
| | state[i] = mjCNSTRSTATE_QUADRATIC; |
| | } |
| | continue; |
| | } |
| |
|
| | |
| |
|
| | |
| | if (type[i] != mjCNSTR_CONTACT_ELLIPTIC) { |
| | |
| | if (jar[i] >= 0) { |
| | force[i] = 0; |
| |
|
| | state[i] = mjCNSTRSTATE_SATISFIED; |
| | } |
| |
|
| | |
| | else { |
| | if (cost) { |
| | s += 0.5*D[i]*jar[i]*jar[i]; |
| | } |
| | state[i] = mjCNSTRSTATE_QUADRATIC; |
| | } |
| | } |
| |
|
| | |
| | else { |
| | |
| | mjContact* con = contact + id[i]; |
| | mjtNum mu = con->mu, *friction = con->friction; |
| | int dim = con->dim; |
| |
|
| | |
| | mjtNum U[6]; |
| | U[0] = jar[i]*mu; |
| | for (int j=1; j < dim; j++) { |
| | U[j] = jar[i+j]*friction[j-1]; |
| | } |
| |
|
| | |
| | mjtNum N = U[0]; |
| | mjtNum T = mju_norm(U+1, dim-1); |
| |
|
| | |
| | if (N >= mu*T || (T <= 0 && N >= 0)) { |
| | mju_zero(force+i, dim); |
| | state[i] = mjCNSTRSTATE_SATISFIED; |
| | } |
| |
|
| | |
| | else if (mu*N+T <= 0 || (T <= 0 && N < 0)) { |
| | if (cost) { |
| | for (int j=0; j < dim; j++) { |
| | s += 0.5*D[i+j]*jar[i+j]*jar[i+j]; |
| | } |
| | } |
| | state[i] = mjCNSTRSTATE_QUADRATIC; |
| | } |
| |
|
| | |
| | else { |
| | |
| | mjtNum Dm = D[i]/(mu*mu*(1+mu*mu)); |
| | mjtNum NmT = N - mu*T; |
| |
|
| | if (cost) { |
| | s += 0.5*Dm*NmT*NmT; |
| | } |
| |
|
| | |
| | force[i] = -Dm*NmT*mu; |
| | for (int j=1; j < dim; j++) { |
| | force[i+j] = -force[i]/T*U[j]*friction[j-1]; |
| | } |
| |
|
| | |
| | state[i] = mjCNSTRSTATE_CONE; |
| |
|
| | |
| | if (flg_coneHessian) { |
| | |
| | mjtNum* H = contact[id[i]].H; |
| |
|
| | |
| | mjtNum scl = -mu/T; |
| | H[0] = 1; |
| | for (int j=1; j < dim; j++) { |
| | H[j] = scl*U[j]; |
| | } |
| |
|
| | |
| | scl = mu*N/(T*T*T); |
| | for (int k=1; k < dim; k++) { |
| | for (int j=k; j < dim; j++) { |
| | H[k*dim+j] = scl*U[j]*U[k]; |
| | } |
| | } |
| |
|
| | |
| | scl = mu*mu - mu*N/T; |
| | for (int j=1; j < dim; j++) { |
| | H[j*(dim+1)] += scl; |
| | } |
| |
|
| | |
| | for (int k=0; k < dim; k++) { |
| | scl = Dm * (k == 0 ? mu : friction[k-1]); |
| | for (int j=k; j < dim; j++) { |
| | H[k*dim+j] *= scl * (j == 0 ? mu : friction[j-1]); |
| | } |
| | } |
| |
|
| | |
| | for (int k=0; k < dim; k++) { |
| | for (int j=k+1; j < dim; j++) { |
| | H[j*dim+k] = H[k*dim+j]; |
| | } |
| | } |
| | } |
| | } |
| |
|
| | |
| | for (int j=1; j < dim; j++) { |
| | state[i+j] = state[i]; |
| | } |
| |
|
| | |
| | i += (dim-1); |
| | } |
| | } |
| |
|
| | |
| | if (cost) { |
| | *cost = s; |
| | } |
| | } |
| |
|
| |
|
| |
|
| | |
| | |
| | void mj_constraintUpdate(const mjModel* m, mjData* d, const mjtNum* jar, |
| | mjtNum cost[1], int flg_coneHessian) { |
| | mj_constraintUpdate_impl(d->ne, d->nf, d->nefc, d->efc_D, d->efc_R, d->efc_frictionloss, |
| | jar, d->efc_type, d->efc_id, d->contact, d->efc_state, d->efc_force, |
| | cost, flg_coneHessian); |
| | mj_mulJacTVec(m, d, d->qfrc_constraint, d->efc_force); |
| | } |
| |
|