| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| |
|
| | #include "engine/engine_island.h" |
| |
|
| | #include <stdio.h> |
| | #include <stddef.h> |
| | #include <string.h> |
| |
|
| | #include <mujoco/mjdata.h> |
| | #include <mujoco/mjmodel.h> |
| | #include <mujoco/mjsan.h> |
| | #include <mujoco/mjxmacro.h> |
| | #include "engine/engine_core_constraint.h" |
| | #include "engine/engine_io.h" |
| | #include "engine/engine_support.h" |
| | #include "engine/engine_util_errmem.h" |
| | #include "engine/engine_util_misc.h" |
| | #include "engine/engine_util_sparse.h" |
| |
|
| | #ifdef MEMORY_SANITIZER |
| | #include <sanitizer/msan_interface.h> |
| | #endif |
| |
|
| |
|
| | |
| |
|
| | |
| | static void clearIsland(mjData* d, size_t parena) { |
| | #define X(type, name, nr, nc) d->name = NULL; |
| | MJDATA_ARENA_POINTERS_ISLAND |
| | #undef X |
| | d->nefc = 0; |
| | d->nisland = 0; |
| | d->nidof = 0; |
| | d->parena = parena; |
| |
|
| | |
| | #ifdef ADDRESS_SANITIZER |
| | ASAN_POISON_MEMORY_REGION( |
| | (char*)d->arena + d->parena, d->narena - d->pstack - d->parena); |
| | #endif |
| | } |
| |
|
| |
|
| |
|
| | |
| | static int arenaAllocIsland(const mjModel* m, mjData* d) { |
| | #undef MJ_M |
| | #define MJ_M(n) m->n |
| | #undef MJ_D |
| | #define MJ_D(n) d->n |
| |
|
| | size_t parena_old = d->parena; |
| |
|
| | #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); \ |
| | clearIsland(d, parena_old); \ |
| | return 0; \ |
| | } |
| |
|
| | MJDATA_ARENA_POINTERS_ISLAND |
| |
|
| | #undef X |
| |
|
| | #undef MJ_M |
| | #define MJ_M(n) n |
| | #undef MJ_D |
| | #define MJ_D(n) n |
| | return 1; |
| | } |
| |
|
| |
|
| |
|
| | |
| |
|
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | int mj_floodFill(int* island, int nr, const int* rownnz, const int* rowadr, const int* colind, |
| | int* stack) { |
| | |
| | int nisland = 0; |
| | for (int i=0; i < nr; i++) island[i] = -1; |
| |
|
| | |
| | for (int i=0; i < nr; i++) { |
| | |
| | if (island[i] != -1 || !rownnz[i]) { |
| | continue; |
| | } |
| |
|
| | |
| | int nstack = 0; |
| | stack[nstack++] = i; |
| |
|
| | |
| | while (nstack) { |
| | |
| | int v = stack[--nstack]; |
| |
|
| | |
| | if (island[v] != -1) { |
| | continue; |
| | } |
| |
|
| | |
| | island[v] = nisland; |
| |
|
| | |
| | mju_copyInt(stack + nstack, colind + rowadr[v], rownnz[v]); |
| | nstack += rownnz[v]; |
| | } |
| |
|
| | |
| | nisland++; |
| | } |
| |
|
| | return nisland; |
| | } |
| |
|
| |
|
| |
|
| | |
| | |
| | |
| | |
| | static int treeNext(const mjModel* m, const mjData* d, int tree, int i, int *index) { |
| | int tree_next = -1; |
| | int j; |
| |
|
| | |
| | if (mj_isSparse(m)) { |
| | int rownnz = d->efc_J_rownnz[i]; |
| | int* colind = d->efc_J_colind + d->efc_J_rowadr[i]; |
| |
|
| | |
| | for (j=(*index); j < rownnz; j++) { |
| | int tree_j = m->dof_treeid[colind[j]]; |
| | if (tree_j != tree) { |
| | |
| | tree_next = tree_j; |
| | break; |
| | } |
| | } |
| | } |
| |
|
| | |
| | else { |
| | int nv = m->nv; |
| |
|
| | |
| | for (j=(*index); j < nv; j++) { |
| | if (d->efc_J[nv*i + j]) { |
| | int tree_j = m->dof_treeid[j]; |
| | if (tree_j != tree) { |
| | |
| | tree_next = tree_j; |
| | break; |
| | } |
| | } |
| | } |
| | } |
| |
|
| | |
| | *index = j; |
| |
|
| | return tree_next; |
| | } |
| |
|
| |
|
| |
|
| | |
| | |
| | |
| | static int treeFirst(const mjModel* m, const mjData* d, int tree[2], int i) { |
| | int efc_type = d->efc_type[i]; |
| | int efc_id = d->efc_id[i]; |
| |
|
| | |
| | tree[0] = -1; |
| | tree[1] = -1; |
| |
|
| | |
| |
|
| | |
| | if (efc_type == mjCNSTR_FRICTION_DOF) { |
| | tree[0] = m->dof_treeid[efc_id]; |
| | return -1; |
| | } |
| |
|
| | |
| | if (efc_type == mjCNSTR_LIMIT_JOINT) { |
| | tree[0] = m->dof_treeid[m->jnt_dofadr[efc_id]]; |
| | return -1; |
| | } |
| |
|
| | |
| | if (efc_type == mjCNSTR_CONTACT_FRICTIONLESS || |
| | efc_type == mjCNSTR_CONTACT_PYRAMIDAL || |
| | efc_type == mjCNSTR_CONTACT_ELLIPTIC) { |
| | int g1 = d->contact[efc_id].geom[0]; |
| | int g2 = d->contact[efc_id].geom[1]; |
| |
|
| | |
| | if (g1 >=0 && g2 >= 0) { |
| | tree[0] = m->body_treeid[m->geom_bodyid[g1]]; |
| | tree[1] = m->body_treeid[m->geom_bodyid[g2]]; |
| |
|
| | |
| | if (tree[0] < 0) { |
| | if (tree[1] < 0) { |
| | mjERROR("contact %d is between two static bodies", efc_id); |
| | } else { |
| | int tmp = tree[0]; |
| | tree[0] = tree[1]; |
| | tree[1] = tmp; |
| | } |
| | } |
| |
|
| | return -1; |
| | } |
| | } |
| |
|
| | |
| | if (efc_type == mjCNSTR_EQUALITY) { |
| | mjtEq eq_type = m->eq_type[efc_id]; |
| | if (eq_type == mjEQ_CONNECT || eq_type == mjEQ_WELD) { |
| | int b1 = m->eq_obj1id[efc_id]; |
| | int b2 = m->eq_obj2id[efc_id]; |
| |
|
| | |
| | if (m->eq_objtype[efc_id] == mjOBJ_SITE) { |
| | b1 = m->site_bodyid[b1]; |
| | b2 = m->site_bodyid[b2]; |
| | } |
| |
|
| | tree[0] = m->body_treeid[b1]; |
| | tree[1] = m->body_treeid[b2]; |
| |
|
| | |
| | if (tree[0] < 0) { |
| | if (tree[1] < 0) { |
| | mjERROR("equality %d is between two static bodies", efc_id); |
| | } else { |
| | int tmp = tree[0]; |
| | tree[0] = tree[1]; |
| | tree[1] = tmp; |
| | } |
| | } |
| |
|
| | return -1; |
| | } |
| | } |
| |
|
| | |
| | int index = 0; |
| | tree[0] = treeNext(m, d, -1, i, &index); |
| |
|
| | if (tree[0] < 0) { |
| | mjERROR("no tree found for constraint %d", i); |
| | } |
| |
|
| | return index; |
| | } |
| |
|
| |
|
| |
|
| | |
| | |
| | static int addEdge(int* treenedge, int* edge, int nedge, int tree1, int tree2, int nedge_max) { |
| | |
| | if (tree1 == -1 && tree2 == -1) { |
| | mjERROR("self-edge of the static tree"); |
| | return 0; |
| | } |
| | if (tree1 == -1) tree1 = tree2; |
| | if (tree2 == -1) tree2 = tree1; |
| |
|
| | |
| | int p1 = nedge ? edge[2*nedge - 2] : -1; |
| | int p2 = nedge ? edge[2*nedge - 1] : -1; |
| |
|
| | |
| | if (tree1 == tree2) { |
| | |
| | if (nedge && tree1 == p1 && tree1 == p2) { |
| | return nedge; |
| | } |
| |
|
| | |
| | if (nedge >= nedge_max) { |
| | mjERROR("edge array too small"); |
| | return 0; |
| | } |
| |
|
| | |
| | edge[2*nedge + 0] = tree1; |
| | edge[2*nedge + 1] = tree1; |
| | treenedge[tree1]++; |
| | return nedge + 1; |
| | } |
| |
|
| | |
| | if (nedge && ((tree1 == p1 && tree2 == p2) || (tree1 == p2 && tree2 == p1))) { |
| | |
| | return nedge; |
| | } |
| |
|
| | |
| | if (nedge + 2 > nedge_max) { |
| | mjERROR("edge array too small"); |
| | return 0; |
| | } |
| |
|
| | |
| | edge[2*nedge + 0] = tree1; |
| | edge[2*nedge + 1] = tree2; |
| | edge[2*nedge + 2] = tree2; |
| | edge[2*nedge + 3] = tree1; |
| | treenedge[tree1]++; |
| | treenedge[tree2]++; |
| | return nedge + 2; |
| | } |
| |
|
| |
|
| |
|
| | |
| | static int findEdges(const mjModel* m, const mjData* d, int* treenedge, int* edge, int nedge_max) { |
| | int nefc = d->nefc; |
| | int efc_type = -1; |
| | int efc_id = -1; |
| |
|
| | |
| | mju_zeroInt(treenedge, m->ntree); |
| |
|
| | int nedge = 0; |
| | for (int i=0; i < nefc; i++) { |
| | |
| | if (efc_type == d->efc_type[i] && efc_id == d->efc_id[i]) { |
| | |
| | if (!(efc_type == mjCNSTR_EQUALITY && m->eq_type[efc_id] == mjEQ_FLEX)) { |
| | continue; |
| | } |
| | } |
| | efc_type = d->efc_type[i]; |
| | efc_id = d->efc_id[i]; |
| |
|
| | int tree[2]; |
| | int index = treeFirst(m, d, tree, i); |
| | int tree1 = tree[0]; |
| | int tree2 = tree[1]; |
| |
|
| | |
| | if (index == -1) { |
| | nedge = addEdge(treenedge, edge, nedge, tree1, tree2 == -1 ? tree1 : tree2, nedge_max); |
| | continue; |
| | } |
| |
|
| | |
| | else { |
| | tree2 = treeNext(m, d, tree1, i, &index); |
| |
|
| | if (tree2 == -1) { |
| | |
| | nedge = addEdge(treenedge, edge, nedge, tree1, tree1, nedge_max); |
| | } else { |
| | |
| | nedge = addEdge(treenedge, edge, nedge, tree1, tree2, nedge_max); |
| | int tree3 = treeNext(m, d, tree2, i, &index); |
| | while (tree3 > -1 && tree3 != tree2) { |
| | tree1 = tree2; |
| | tree2 = tree3; |
| | nedge = addEdge(treenedge, edge, nedge, tree1, tree2, nedge_max); |
| | tree3 = treeNext(m, d, tree2, i, &index); |
| | } |
| | } |
| | } |
| | } |
| |
|
| | return nedge; |
| | } |
| |
|
| |
|
| |
|
| | |
| |
|
| | |
| | |
| | void mj_island(const mjModel* m, mjData* d) { |
| | int nv = m->nv, nefc = d->nefc, ntree=m->ntree; |
| |
|
| | |
| | if (!mjENABLED(mjENBL_ISLAND) || !nefc) { |
| | d->nisland = d->nidof = 0; |
| | return; |
| | } |
| |
|
| | mj_markStack(d); |
| |
|
| | |
| | int* edge = mjSTACKALLOC(d, 2*d->nJ, int); |
| |
|
| | |
| | int* rownnz = mjSTACKALLOC(d, ntree, int); |
| | int nedge = findEdges(m, d, rownnz, edge, d->nJ); |
| |
|
| | |
| | int* rowadr = mjSTACKALLOC(d, ntree, int); |
| | rowadr[0] = 0; |
| | for (int r=1; r < ntree; r++) { |
| | rowadr[r] = rowadr[r-1] + rownnz[r-1]; |
| | rownnz[r-1] = 0; |
| | } |
| | rownnz[ntree-1] = 0; |
| |
|
| | |
| | int* colind = mjSTACKALLOC(d, nedge, int); |
| | for (int e=0; e < nedge; e++) { |
| | int row = edge[2*e]; |
| | int col = edge[2*e + 1]; |
| | colind[rowadr[row] + rownnz[row]++] = col; |
| | } |
| |
|
| | |
| | int* tree_island = mjSTACKALLOC(d, ntree, int); |
| | int* stack = mjSTACKALLOC(d, nedge, int); |
| | d->nisland = mj_floodFill(tree_island, ntree, rownnz, rowadr, colind, stack); |
| |
|
| | |
| | if (!d->nisland) { |
| | d->nidof = 0; |
| | mj_freeStack(d); |
| | return; |
| | } |
| |
|
| | |
| | int nidof = 0; |
| | for (int i=0; i < nv; i++) { |
| | nidof += (tree_island[m->dof_treeid[i]] >= 0); |
| | } |
| | d->nidof = nidof; |
| |
|
| | |
| | if (!arenaAllocIsland(m, d)) { |
| | mj_freeStack(d); |
| | return; |
| | } |
| |
|
| | |
| | int nisland = d->nisland; |
| |
|
| |
|
| | |
| |
|
| | |
| | mju_zeroInt(d->island_nv, nisland); |
| | for (int i=0; i < nv; i++) { |
| | |
| | int island = tree_island[m->dof_treeid[i]]; |
| | d->dof_island[i] = island; |
| |
|
| | |
| | if (island >= 0) { |
| | d->island_nv[island]++; |
| | } |
| | } |
| |
|
| | |
| | d->island_idofadr[0] = 0; |
| | for (int i=1; i < nisland; i++) { |
| | d->island_idofadr[i] = d->island_idofadr[i-1] + d->island_nv[i-1]; |
| | } |
| |
|
| | |
| | int* island_nv2 = mjSTACKALLOC(d, nisland + 1, int); |
| | mju_zeroInt(island_nv2, nisland + 1); |
| | for (int dof=0; dof < nv; dof++) { |
| | int island = d->dof_island[dof]; |
| | int idof; |
| | if (island >= 0) { |
| | |
| | idof = d->island_idofadr[island] + island_nv2[island]++; |
| | } else { |
| | |
| | idof = nidof + island_nv2[nisland]++; |
| | } |
| |
|
| | d->map_dof2idof[dof] = idof; |
| | d->map_idof2dof[idof] = dof; |
| | } |
| |
|
| | |
| | if (!mju_compare(island_nv2, d->island_nv, nisland)) mjERROR("island_nv miscount"); |
| | if (nidof + island_nv2[nisland] != nv) mjERROR("miscount of unconstrained dofs"); |
| |
|
| | |
| | for (int i=0; i < nisland; i++) { |
| | d->island_dofadr[i] = d->map_idof2dof[d->island_idofadr[i]]; |
| | } |
| |
|
| | |
| | mju_blockDiagSparse(d->iLD, d->iM_rownnz, d->iM_rowadr, d->iM_colind, |
| | d->qLD, d->M_rownnz, d->M_rowadr, d->M_colind, |
| | nidof, nisland, |
| | d->map_idof2dof, d->map_dof2idof, |
| | d->island_idofadr, d->island_idofadr, |
| | d->iM, d->M); |
| | mju_gather(d->iLDiagInv, d->qLDiagInv, d->map_idof2dof, nidof); |
| |
|
| |
|
| | |
| |
|
| | |
| | mju_zeroInt(d->island_ne, nisland); |
| | mju_zeroInt(d->island_nf, nisland); |
| | mju_zeroInt(d->island_nefc, nisland); |
| | for (int i=0; i < nefc; i++) { |
| | int tree[2]; |
| | treeFirst(m, d, tree, i); |
| | int island = tree_island[tree[0]]; |
| | d->efc_island[i] = island; |
| | d->island_nefc[island]++; |
| | switch (d->efc_type[i]) { |
| | case mjCNSTR_EQUALITY: |
| | d->island_ne[island]++; |
| | break; |
| | case mjCNSTR_FRICTION_DOF: |
| | case mjCNSTR_FRICTION_TENDON: |
| | d->island_nf[island]++; |
| | break; |
| | default: |
| | break; |
| | } |
| | } |
| |
|
| | |
| | d->island_iefcadr[0] = 0; |
| | for (int i=1; i < nisland; i++) { |
| | d->island_iefcadr[i] = d->island_iefcadr[i-1] + d->island_nefc[i-1]; |
| | } |
| |
|
| | |
| | int* island_nefc2 = island_nv2; |
| | mju_zeroInt(island_nefc2, nisland); |
| | for (int c=0; c < nefc; c++) { |
| | int island = d->efc_island[c]; |
| | int ic = d->island_iefcadr[island] + island_nefc2[island]++; |
| | d->map_efc2iefc[c] = ic; |
| | d->map_iefc2efc[ic] = c; |
| | } |
| |
|
| | |
| | if (!mju_compare(island_nefc2, d->island_nefc, nisland)) mjERROR("island_nefc miscount"); |
| |
|
| | |
| | if (!mj_isSparse(m)) { |
| | mju_blockDiag(d->iefc_J, d->efc_J, |
| | nv, nidof, nisland, |
| | d->map_iefc2efc, d->map_idof2dof, |
| | d->island_nefc, d->island_nv, |
| | d->island_iefcadr, d->island_idofadr); |
| | } |
| |
|
| | |
| | else { |
| | |
| | mju_blockDiagSparse(d->iefc_J, d->iefc_J_rownnz, d->iefc_J_rowadr, d->iefc_J_colind, |
| | d->efc_J, d->efc_J_rownnz, d->efc_J_rowadr, d->efc_J_colind, |
| | nefc, nisland, |
| | d->map_iefc2efc, d->map_dof2idof, |
| | d->island_iefcadr, d->island_idofadr, NULL, NULL); |
| |
|
| | |
| | for (int island=0; island < nisland; island++) { |
| | int adr = d->island_iefcadr[island]; |
| | mju_superSparse(d->island_nefc[island], d->iefc_J_rowsuper + adr, |
| | d->iefc_J_rownnz + adr, d->iefc_J_rowadr + adr, d->iefc_J_colind); |
| | } |
| |
|
| | |
| | mju_blockDiagSparse(d->iefc_JT, d->iefc_JT_rownnz, d->iefc_JT_rowadr, d->iefc_JT_colind, |
| | d->efc_JT, d->efc_JT_rownnz, d->efc_JT_rowadr, d->efc_JT_colind, |
| | nidof, nisland, |
| | d->map_idof2dof, d->map_efc2iefc, |
| | d->island_idofadr, d->island_iefcadr, NULL, NULL); |
| |
|
| | |
| | for (int island=0; island < nisland; island++) { |
| | int adr = d->island_idofadr[island]; |
| | mju_superSparse(d->island_nv[island], d->iefc_JT_rowsuper + adr, |
| | d->iefc_JT_rownnz + adr, d->iefc_JT_rowadr + adr, d->iefc_JT_colind); |
| | } |
| | } |
| |
|
| | |
| | mju_gatherInt(d->iefc_type, d->efc_type, d->map_iefc2efc, nefc); |
| | mju_gatherInt(d->iefc_id, d->efc_id, d->map_iefc2efc, nefc); |
| | mju_gather(d->iefc_frictionloss, d->efc_frictionloss, d->map_iefc2efc, nefc); |
| | mju_gather(d->iefc_D, d->efc_D, d->map_iefc2efc, nefc); |
| | mju_gather(d->iefc_R, d->efc_R, d->map_iefc2efc, nefc); |
| |
|
| | mj_freeStack(d); |
| | } |
| |
|