| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| |
|
| | #include "engine/engine_collision_convex.h" |
| |
|
| | #include <float.h> |
| | #include <stddef.h> |
| |
|
| | #include <ccd/ccd.h> |
| | #include <ccd/vec3.h> |
| |
|
| | #include <mujoco/mjdata.h> |
| | #include <mujoco/mjmacro.h> |
| | #include <mujoco/mjmodel.h> |
| | #include "engine/engine_collision_gjk.h" |
| | #include "engine/engine_collision_primitive.h" |
| | #include "engine/engine_io.h" |
| | #include "engine/engine_util_blas.h" |
| | #include "engine/engine_util_errmem.h" |
| | #include "engine/engine_util_misc.h" |
| | #include "engine/engine_util_spatial.h" |
| |
|
| |
|
| | |
| | static void* ccd_allocate(void* data, size_t nbytes) { |
| | mj_markStack((mjData*)data); |
| | return mj_stackAllocByte((mjData*)data, nbytes, sizeof(mjtNum)); |
| | } |
| |
|
| | |
| | static void ccd_free(void* data, void* buffer) { |
| | mj_freeStack((mjData*)data); |
| | } |
| |
|
| | |
| | static int mjc_penetration(const mjModel* m, mjCCDObj* obj1, mjCCDObj* obj2, |
| | const ccd_t* ccd, ccd_real_t* depth, ccd_vec3_t* dir, ccd_vec3_t* pos) { |
| | |
| | if (mjDISABLED(mjDSBL_NATIVECCD)) { |
| | return ccdMPRPenetration(obj1, obj2, ccd, depth, dir, pos); |
| | } |
| |
|
| | mjCCDConfig config; |
| | mjCCDStatus status; |
| |
|
| | |
| | config.max_iterations = ccd->max_iterations, |
| | config.tolerance = ccd->mpr_tolerance, |
| | config.max_contacts = 1; |
| | config.dist_cutoff = 0; |
| | config.context = (void*)obj1->data; |
| | config.alloc = ccd_allocate; |
| | config.free = ccd_free; |
| |
|
| | mjtNum dist = mjc_ccd(&config, &status, obj1, obj2); |
| | if (dist < 0) { |
| | if (depth) *depth = -dist; |
| | if (dir) { |
| | mju_sub3(dir->v, status.x1, status.x2); |
| | mju_normalize3(dir->v); |
| | } |
| | if (pos) { |
| | pos->v[0] = 0.5 * (status.x1[0] + status.x2[0]); |
| | pos->v[1] = 0.5 * (status.x1[1] + status.x2[1]); |
| | pos->v[2] = 0.5 * (status.x1[2] + status.x2[2]); |
| | } |
| | return 0; |
| | } |
| | if (depth) *depth = 0; |
| | if (dir) mju_zero3(dir->v); |
| | if (pos) mju_zero3(dir->v); |
| | return 1; |
| | } |
| |
|
| |
|
| |
|
| | |
| | void mjccd_center(const void *obj, ccd_vec3_t *center) { |
| | mjc_center(center->v, (const mjCCDObj*) obj); |
| | } |
| |
|
| | |
| | void mjc_center(mjtNum res[3], const mjCCDObj *obj) { |
| | int g = obj->geom; |
| | int f = obj->flex; |
| | int e = obj->elem; |
| | int v = obj->vert; |
| |
|
| | |
| | if (g >= 0) { |
| | mju_copy3(res, obj->data->geom_xpos + 3*g); |
| | } |
| |
|
| | |
| | else if (e >= 0) { |
| | mju_copy3(res, obj->data->flexelem_aabb + 6*(obj->model->flex_elemadr[f]+e)); |
| | } |
| |
|
| | |
| | else { |
| | mju_copy3(res, obj->data->flexvert_xpos + 3*(obj->model->flex_vertadr[f]+v)); |
| | } |
| | } |
| |
|
| |
|
| |
|
| | |
| | static void mjc_prism_center(mjtNum res[3], const mjCCDObj* obj) { |
| | |
| | mju_zero3(res); |
| | for (int i=0; i < 6; i++) { |
| | mju_addTo3(res, obj->prism[i]); |
| | } |
| | mju_scl3(res, res, 1.0/6.0); |
| | } |
| |
|
| |
|
| |
|
| | |
| | static void mjccd_prism_center(const void *obj, ccd_vec3_t *center) { |
| | mjc_prism_center(center->v, (const mjCCDObj*) obj); |
| | } |
| |
|
| | |
| |
|
| | |
| | static inline void mulMatTVec3(mjtNum res[3], const mjtNum mat[9], const mjtNum dir[3]) { |
| | |
| | res[0] = mat[0]*dir[0] + mat[3]*dir[1] + mat[6]*dir[2]; |
| | res[1] = mat[1]*dir[0] + mat[4]*dir[1] + mat[7]*dir[2]; |
| | res[2] = mat[2]*dir[0] + mat[5]*dir[1] + mat[8]*dir[2]; |
| | } |
| |
|
| |
|
| |
|
| | |
| | static inline void localToGlobal(mjtNum res[3], const mjtNum mat[9], const mjtNum dir[3], |
| | const mjtNum pos[3]) { |
| | |
| | res[0] = mat[0]*dir[0] + mat[1]*dir[1] + mat[2]*dir[2]; |
| | res[1] = mat[3]*dir[0] + mat[4]*dir[1] + mat[5]*dir[2]; |
| | res[2] = mat[6]*dir[0] + mat[7]*dir[1] + mat[8]*dir[2]; |
| | res[0] += pos[0]; |
| | res[1] += pos[1]; |
| | res[2] += pos[2]; |
| | } |
| |
|
| |
|
| |
|
| | |
| | void mjc_pointSupport(mjtNum res[3], mjCCDObj* obj, const mjtNum dir[3]) { |
| | const mjtNum* pos = obj->data->geom_xpos + 3*obj->geom; |
| | res[0] = pos[0]; |
| | res[1] = pos[1]; |
| | res[2] = pos[2]; |
| | } |
| |
|
| |
|
| |
|
| | |
| | static void mjc_sphereSupport(mjtNum res[3], mjCCDObj* obj, const mjtNum dir[3]) { |
| | const mjModel* m = obj->model; |
| | const mjData* d = obj->data; |
| |
|
| | |
| | const mjtNum* pos = d->geom_xpos + 3*obj->geom; |
| | mjtNum radius = m->geom_size[3*obj->geom]; |
| |
|
| | res[0] = radius*dir[0] + pos[0]; |
| | res[1] = radius*dir[1] + pos[1]; |
| | res[2] = radius*dir[2] + pos[2]; |
| | } |
| |
|
| |
|
| |
|
| | |
| | void mjc_lineSupport(mjtNum res[3], mjCCDObj* obj, const mjtNum dir[3]) { |
| | const mjModel* m = obj->model; |
| | const mjData* d = obj->data; |
| |
|
| | |
| | int i = 3*obj->geom; |
| | const mjtNum* mat = d->geom_xmat + 3*i; |
| | const mjtNum* pos = d->geom_xpos + i; |
| | mjtNum length = m->geom_size[i+1]; |
| |
|
| | |
| | mjtNum local_dir[3], tmp[3]; |
| | mulMatTVec3(local_dir, mat, dir); |
| |
|
| | tmp[0] = 0; |
| | tmp[1] = 0; |
| | tmp[2] = (local_dir[2] >= 0 ? length : -length); |
| |
|
| | |
| | localToGlobal(res, mat, tmp, pos); |
| | } |
| |
|
| |
|
| |
|
| | |
| | static void mjc_capsuleSupport(mjtNum res[3], mjCCDObj* obj, const mjtNum dir[3]) { |
| | const mjModel* m = obj->model; |
| | const mjData* d = obj->data; |
| |
|
| | |
| | int i = 3*obj->geom; |
| | const mjtNum* mat = d->geom_xmat + 3*i; |
| | const mjtNum* pos = d->geom_xpos + i; |
| | mjtNum radius = m->geom_size[i]; |
| | mjtNum length = m->geom_size[i+1]; |
| |
|
| | |
| | mjtNum local_dir[3], tmp[3]; |
| | mulMatTVec3(local_dir, mat, dir); |
| |
|
| | |
| | tmp[0] = local_dir[0] * radius; |
| | tmp[1] = local_dir[1] * radius; |
| | tmp[2] = local_dir[2] * radius; |
| |
|
| | |
| | tmp[2] += (local_dir[2] >= 0 ? length : -length); |
| |
|
| | |
| | localToGlobal(res, mat, tmp, pos); |
| | } |
| |
|
| |
|
| |
|
| | |
| | static void mjc_ellipsoidSupport(mjtNum res[3], mjCCDObj* obj, const mjtNum dir[3]) { |
| | const mjModel* m = obj->model; |
| | const mjData* d = obj->data; |
| |
|
| | |
| | int i = 3*obj->geom; |
| | const mjtNum* mat = d->geom_xmat + 3*i; |
| | const mjtNum* pos = d->geom_xpos + i; |
| | const mjtNum* size = m->geom_size + i; |
| |
|
| | |
| | mjtNum local_dir[3], tmp[3]; |
| | mulMatTVec3(local_dir, mat, dir); |
| |
|
| | |
| | tmp[0] = local_dir[0] * size[0]; |
| | tmp[1] = local_dir[1] * size[1]; |
| | tmp[2] = local_dir[2] * size[2]; |
| |
|
| | mjtNum norm = mju_sqrt(tmp[0]*tmp[0] + tmp[1]*tmp[1] + tmp[2]*tmp[2]); |
| |
|
| | |
| | if (norm < mjMINVAL) { |
| | tmp[0] = size[0]; |
| | tmp[1] = 0; |
| | tmp[2] = 0; |
| | } else { |
| | mjtNum norm_inv = 1/norm; |
| | tmp[0] *= norm_inv * size[0]; |
| | tmp[1] *= norm_inv * size[1]; |
| | tmp[2] *= norm_inv * size[2]; |
| | } |
| |
|
| | |
| | localToGlobal(res, mat, tmp, pos); |
| | } |
| |
|
| |
|
| |
|
| | |
| | static void mjc_cylinderSupport(mjtNum res[3], mjCCDObj* obj, const mjtNum dir[3]) { |
| | const mjModel* m = obj->model; |
| | const mjData* d = obj->data; |
| |
|
| | |
| | int i = 3*obj->geom; |
| | const mjtNum* mat = d->geom_xmat + 3*i; |
| | const mjtNum* pos = d->geom_xpos + i; |
| | const mjtNum* size = m->geom_size + i; |
| |
|
| | |
| | mjtNum local_dir[3], tmp[3]; |
| | mulMatTVec3(local_dir, mat, dir); |
| |
|
| | mjtNum n = local_dir[0]*local_dir[0] + local_dir[1]*local_dir[1]; |
| | if (n > mjMINVAL*mjMINVAL) { |
| | n = size[0] / mju_sqrt(n); |
| | tmp[0] = local_dir[0] * n; |
| | tmp[1] = local_dir[1] * n; |
| | } else { |
| | tmp[0] = tmp[1] = 0; |
| | } |
| |
|
| | |
| | tmp[2] = mju_sign(local_dir[2]) * size[1]; |
| |
|
| | |
| | localToGlobal(res, mat, tmp, pos); |
| | } |
| |
|
| |
|
| |
|
| | |
| | static void mjc_boxSupport(mjtNum res[3], mjCCDObj* obj, const mjtNum dir[3]) { |
| | const mjModel* m = obj->model; |
| | const mjData* d = obj->data; |
| |
|
| | |
| | int i = 3*obj->geom; |
| | const mjtNum* mat = d->geom_xmat + 3*i; |
| | const mjtNum* pos = d->geom_xpos + i; |
| | const mjtNum* size = m->geom_size + i; |
| |
|
| | |
| | mjtNum local_dir[3], tmp[3]; |
| | mulMatTVec3(local_dir, mat, dir); |
| |
|
| | |
| | tmp[0] = (local_dir[0] >= 0 ? 1 : -1) * size[0]; |
| | tmp[1] = (local_dir[1] >= 0 ? 1 : -1) * size[1]; |
| | tmp[2] = (local_dir[2] >= 0 ? 1 : -1) * size[2]; |
| |
|
| | |
| | obj->vertindex = 0; |
| | if (tmp[0] > 0) obj->vertindex |= 1; |
| | if (tmp[1] > 0) obj->vertindex |= 2; |
| | if (tmp[2] > 0) obj->vertindex |= 4; |
| |
|
| | |
| | localToGlobal(res, mat, tmp, pos); |
| | } |
| |
|
| |
|
| |
|
| | |
| | static inline mjtNum dot3f(const mjtNum a[3], const float b[3]) { |
| | return a[0]*(mjtNum)b[0] + a[1]*(mjtNum)b[1] + a[2]*(mjtNum)b[2]; |
| | } |
| |
|
| |
|
| |
|
| | |
| | static void mjc_meshSupport(mjtNum res[3], mjCCDObj* obj, const mjtNum dir[3]) { |
| | const mjModel* m = obj->model; |
| | const mjData* d = obj->data; |
| |
|
| | |
| | int g = obj->geom; |
| | const mjtNum* mat = d->geom_xmat+9*g; |
| | const mjtNum* pos = d->geom_xpos+3*g; |
| | float* verts = m->mesh_vert + 3*m->mesh_vertadr[m->geom_dataid[g]]; |
| | int nverts = m->mesh_vertnum[m->geom_dataid[g]]; |
| |
|
| | mjtNum local_dir[3]; |
| | mulMatTVec3(local_dir, mat, dir); |
| |
|
| | mjtNum max = -FLT_MAX; |
| | int imax = 0; |
| |
|
| | |
| | if (obj->vertindex >= 0) { |
| | imax = obj->vertindex; |
| | max = dot3f(local_dir, verts + 3*imax); |
| | } |
| |
|
| | |
| | for (int i=0; i < nverts; i++) { |
| | mjtNum vdot = dot3f(local_dir, verts + 3*i); |
| |
|
| | |
| | if (vdot > max) { |
| | max = vdot; |
| | imax = i; |
| | } |
| | } |
| |
|
| | |
| | obj->vertindex = imax; |
| |
|
| | local_dir[0] = (mjtNum)verts[3*imax + 0]; |
| | local_dir[1] = (mjtNum)verts[3*imax + 1]; |
| | local_dir[2] = (mjtNum)verts[3*imax + 2]; |
| |
|
| | |
| | localToGlobal(res, mat, local_dir, pos); |
| | } |
| |
|
| |
|
| |
|
| | |
| | static void mjc_hillclimbSupport(mjtNum res[3], mjCCDObj* obj, const mjtNum dir[3]) { |
| | const mjModel* m = obj->model; |
| | const mjData* d = obj->data; |
| |
|
| | |
| | int g = obj->geom; |
| | int graphadr = m->mesh_graphadr[m->geom_dataid[g]]; |
| | int numvert = m->mesh_graph[graphadr]; |
| | int* vert_edgeadr = m->mesh_graph + graphadr + 2; |
| | int* vert_globalid = m->mesh_graph + graphadr + 2 + numvert; |
| | int* edge_localid = m->mesh_graph + graphadr + 2 + 2*numvert; |
| | float* verts = m->mesh_vert + 3*m->mesh_vertadr[m->geom_dataid[g]]; |
| | const mjtNum* mat = d->geom_xmat + 9*g; |
| | const mjtNum* pos = d->geom_xpos+3*g; |
| |
|
| | |
| | mjtNum local_dir[3]; |
| | mulMatTVec3(local_dir, mat, dir); |
| |
|
| | |
| | mjtNum max = -FLT_MAX; |
| | int prev = -1, imax = obj->meshindex < 0 ? 0 : obj->meshindex; |
| | do { |
| | prev = imax; |
| | for (int i = vert_edgeadr[imax]; edge_localid[i] >= 0; i++) { |
| | int idx = 3*vert_globalid[edge_localid[i]]; |
| | mjtNum vdot = dot3f(local_dir, verts + idx); |
| | if (vdot > max) { |
| | max = vdot; |
| | imax = edge_localid[i]; |
| | } |
| | } |
| | } while (imax != prev); |
| |
|
| | |
| | obj->meshindex = imax; |
| |
|
| | |
| | imax = 3*vert_globalid[imax]; |
| | obj->vertindex = imax / 3; |
| | local_dir[0] = (mjtNum)verts[imax + 0]; |
| | local_dir[1] = (mjtNum)verts[imax + 1]; |
| | local_dir[2] = (mjtNum)verts[imax + 2]; |
| |
|
| | |
| | localToGlobal(res, mat, local_dir, pos); |
| | } |
| |
|
| |
|
| |
|
| | |
| | static void mjc_prism_support(mjtNum res[3], mjCCDObj* obj, const mjtNum dir[3]) { |
| | int istart, ibest; |
| | mjtNum best, tmp; |
| |
|
| | |
| | istart = dir[2] < 0 ? 0 : 3; |
| | ibest = istart; |
| | best = mju_dot3(obj->prism[istart], dir); |
| | for (int i=istart+1; i < istart+3; i++) { |
| | if ((tmp = mju_dot3(obj->prism[i], dir)) > best) { |
| | ibest = i; |
| | best = tmp; |
| | } |
| | } |
| |
|
| | |
| | mju_copy3(res, obj->prism[ibest]); |
| | } |
| |
|
| |
|
| |
|
| | |
| | static void mjc_flexSupport(mjtNum res[3], mjCCDObj* obj, const mjtNum dir[3]) { |
| | const mjModel* m = obj->model; |
| | const mjData* d = obj->data; |
| | int f = obj->flex; |
| | int dim = m->flex_dim[f]; |
| |
|
| | |
| | if (obj->elem >= 0) { |
| | int e = obj->elem; |
| | const int* edata = m->flex_elem + m->flex_elemdataadr[f] + e*(dim+1); |
| | const mjtNum* vert = d->flexvert_xpos + 3*m->flex_vertadr[f]; |
| |
|
| | |
| | mju_copy3(res, vert+3*edata[0]); |
| | mjtNum best = mju_dot3(res, dir); |
| | for (int i=1; i <= dim; i++) { |
| | mjtNum dot = mju_dot3(vert+3*edata[i], dir); |
| |
|
| | |
| | if (dot > best) { |
| | best = dot; |
| | mju_copy3(res, vert+3*edata[i]); |
| | } |
| | } |
| |
|
| | |
| | mju_addToScl3(res, dir, m->flex_radius[f] + 0.5*obj->margin); |
| | return; |
| | } |
| |
|
| | |
| | else { |
| | const mjtNum* vert = d->flexvert_xpos + 3*(m->flex_vertadr[f] + obj->vert); |
| | mju_addScl3(res, vert, dir, m->flex_radius[f] + 0.5*obj->margin); |
| | return; |
| | } |
| | } |
| |
|
| |
|
| |
|
| | |
| | void mjccd_support(const void *_obj, const ccd_vec3_t *_dir, ccd_vec3_t *vec) { |
| | mjCCDObj *obj = (mjCCDObj *)_obj; |
| | mjtNum *res = vec->v; |
| | const mjtNum *dir = _dir->v; |
| | const mjModel* m = obj->model; |
| | const mjData* d = obj->data; |
| | int g = obj->geom; |
| |
|
| | if (g < 0) { |
| | int f = obj->flex; |
| | int dim = m->flex_dim[f]; |
| |
|
| | |
| | if (obj->elem >= 0) { |
| | int e = obj->elem; |
| | const int* edata = m->flex_elem + m->flex_elemdataadr[f] + e*(dim+1); |
| | const mjtNum* vert = d->flexvert_xpos + 3*m->flex_vertadr[f]; |
| |
|
| | |
| | mju_copy3(res, vert+3*edata[0]); |
| | mjtNum best = mju_dot3(res, dir); |
| | for (int i=1; i <= dim; i++) { |
| | mjtNum dot = mju_dot3(vert+3*edata[i], dir); |
| |
|
| | |
| | if (dot > best) { |
| | best = dot; |
| | mju_copy3(res, vert+3*edata[i]); |
| | } |
| | } |
| |
|
| | |
| | mju_addToScl3(res, dir, m->flex_radius[f] + 0.5*obj->margin); |
| | return; |
| | } |
| |
|
| | |
| | else { |
| | const mjtNum* vert = d->flexvert_xpos + 3*(m->flex_vertadr[f] + obj->vert); |
| | mju_addScl3(res, vert, dir, m->flex_radius[f] + 0.5*obj->margin); |
| | return; |
| | } |
| | } |
| |
|
| | float* vertdata; |
| | int ibest, graphadr, numvert, change, locid; |
| | int *vert_edgeadr, *vert_globalid, *edge_localid; |
| | mjtNum tmp, vdot; |
| |
|
| | const mjtNum* size = m->geom_size+3*g; |
| | mjtNum local_dir[3]; |
| |
|
| | |
| | mju_mulMatTVec3(local_dir, d->geom_xmat+9*g, dir); |
| |
|
| | |
| | switch ((mjtGeom) obj->geom_type) { |
| | case mjGEOM_SPHERE: |
| | mju_scl3(res, local_dir, size[0]); |
| | break; |
| |
|
| | case mjGEOM_CAPSULE: |
| | |
| | mju_scl3(res, local_dir, size[0]); |
| |
|
| | |
| | res[2] += mju_sign(local_dir[2]) * size[1]; |
| | break; |
| |
|
| | case mjGEOM_ELLIPSOID: |
| | |
| | for (int i=0; i < 3; i++) { |
| | res[i] = local_dir[i] * size[i]; |
| | } |
| | mju_normalize3(res); |
| |
|
| | |
| | for (int i=0; i < 3; i++) { |
| | res[i] *= size[i]; |
| | } |
| | break; |
| |
|
| | case mjGEOM_CYLINDER: |
| | |
| | tmp = mju_sqrt(local_dir[0]*local_dir[0] + local_dir[1]*local_dir[1]); |
| | if (tmp > mjMINVAL) { |
| | res[0] = local_dir[0]/tmp*size[0]; |
| | res[1] = local_dir[1]/tmp*size[0]; |
| | } else { |
| | res[0] = res[1] = 0; |
| | } |
| |
|
| | |
| | res[2] = mju_sign(local_dir[2]) * size[1]; |
| | break; |
| |
|
| | case mjGEOM_BOX: |
| | for (int i=0; i < 3; i++) { |
| | res[i] = mju_sign(local_dir[i]) * size[i]; |
| | } |
| | break; |
| |
|
| | case mjGEOM_MESH: |
| | case mjGEOM_SDF: |
| | |
| | vertdata = m->mesh_vert + 3*m->mesh_vertadr[m->geom_dataid[g]]; |
| | tmp = -1E+10; |
| | ibest = -1; |
| |
|
| | |
| | if (m->mesh_graphadr[m->geom_dataid[g]] < 0) { |
| | |
| | for (int i=0; i < m->mesh_vertnum[m->geom_dataid[g]]; i++) { |
| | |
| | vdot = local_dir[0] * (mjtNum)vertdata[3*i] + |
| | local_dir[1] * (mjtNum)vertdata[3*i+1] + |
| | local_dir[2] * (mjtNum)vertdata[3*i+2]; |
| |
|
| | |
| | if (vdot > tmp) { |
| | tmp = vdot; |
| | ibest = i; |
| | } |
| | } |
| |
|
| | |
| | obj->meshindex = ibest; |
| | } |
| |
|
| | |
| | else { |
| | |
| | graphadr = m->mesh_graphadr[m->geom_dataid[g]]; |
| | numvert = m->mesh_graph[graphadr]; |
| | vert_edgeadr = m->mesh_graph + graphadr + 2; |
| | vert_globalid = m->mesh_graph + graphadr + 2 + numvert; |
| | edge_localid = m->mesh_graph + graphadr + 2 + 2*numvert; |
| |
|
| | |
| | ibest = obj->meshindex < 0 ? 0 : obj->meshindex; |
| | tmp = local_dir[0] * (mjtNum)vertdata[3*vert_globalid[ibest]+0] + |
| | local_dir[1] * (mjtNum)vertdata[3*vert_globalid[ibest]+1] + |
| | local_dir[2] * (mjtNum)vertdata[3*vert_globalid[ibest]+2]; |
| |
|
| | |
| | change = 1; |
| | while (change) { |
| | |
| | change = 0; |
| | int i = vert_edgeadr[ibest]; |
| | while ((locid=edge_localid[i]) >= 0) { |
| | |
| | vdot = local_dir[0] * (mjtNum)vertdata[3*vert_globalid[locid]] + |
| | local_dir[1] * (mjtNum)vertdata[3*vert_globalid[locid]+1] + |
| | local_dir[2] * (mjtNum)vertdata[3*vert_globalid[locid]+2]; |
| |
|
| | |
| | if (vdot > tmp) { |
| | tmp = vdot; |
| | ibest = locid; |
| | change = 1; |
| | } |
| |
|
| | |
| | i++; |
| | } |
| | } |
| |
|
| | |
| | obj->meshindex = ibest; |
| |
|
| | |
| | ibest = vert_globalid[ibest]; |
| | } |
| |
|
| | |
| | if (ibest < 0) { |
| | mju_warning("mesh_support could not find support vertex"); |
| | mju_zero3(res); |
| | } |
| |
|
| | |
| | else { |
| | for (int i=0; i < 3; i++) { |
| | res[i] = (mjtNum)vertdata[3*ibest + i]; |
| | } |
| | } |
| | break; |
| |
|
| | default: |
| | mjERROR("ccd support function is undefined for geom type %d", m->geom_type[g]); |
| | } |
| |
|
| | |
| | for (int i=0; i < 3; i++) { |
| | res[i] += local_dir[i] * obj->margin/2; |
| | } |
| |
|
| | |
| | mju_mulMatVec3(res, d->geom_xmat+9*g, res); |
| |
|
| | |
| | mju_addTo3(res, d->geom_xpos+3*g); |
| | } |
| |
|
| |
|
| |
|
| | |
| | static void mjccd_prism_support(const void *obj, const ccd_vec3_t *dir, ccd_vec3_t *vec) { |
| | mjc_prism_support(vec->v, (mjCCDObj*) obj, dir->v); |
| | } |
| |
|
| | |
| |
|
| | |
| | void mjc_initCCDObj(mjCCDObj* obj, const mjModel* m, const mjData* d, int g, mjtNum margin) { |
| | obj->model = m; |
| | obj->data = d; |
| | obj->geom = g; |
| | obj->margin = margin; |
| | obj->center = mjc_center; |
| | obj->vertindex = -1; |
| | obj->meshindex = -1; |
| | obj->flex = -1; |
| | obj->elem = -1; |
| | obj->vert = -1; |
| | mju_zero4(obj->rotate); |
| | obj->rotate[0] = 1; |
| | if (g >= 0) { |
| | obj->geom_type = m->geom_type[g]; |
| | switch ((mjtGeom) obj->geom_type) { |
| | case mjGEOM_ELLIPSOID: |
| | obj->support = mjc_ellipsoidSupport; |
| | break; |
| | case mjGEOM_MESH: |
| | case mjGEOM_SDF: |
| | if (m->mesh_graphadr[m->geom_dataid[g]] < 0 || |
| | m->mesh_vertnum[m->geom_dataid[g]] < mjMESH_HILLCLIMB_MIN) { |
| | obj->support = mjc_meshSupport; |
| | } else { |
| | obj->support = mjc_hillclimbSupport; |
| | } |
| | break; |
| | case mjGEOM_SPHERE: |
| | obj->support = mjc_sphereSupport; |
| | break; |
| | case mjGEOM_CAPSULE: |
| | obj->support = mjc_capsuleSupport; |
| | break; |
| | case mjGEOM_CYLINDER: |
| | obj->support = mjc_cylinderSupport; |
| | break; |
| | case mjGEOM_BOX: |
| | obj->support = mjc_boxSupport; |
| | break; |
| | case mjGEOM_HFIELD: |
| | obj->center = mjc_prism_center; |
| | obj->support = mjc_prism_support; |
| | break; |
| | default: |
| | obj->support = NULL; |
| | break; |
| | } |
| | } else { |
| | obj->geom_type = mjGEOM_FLEX; |
| | obj->support = mjc_flexSupport; |
| | } |
| | } |
| |
|
| |
|
| |
|
| | |
| | static void mjc_setCCDObjFlex(mjCCDObj* obj, int flex, int elem, int vert) { |
| | obj->flex = flex; |
| | obj->elem = elem; |
| | obj->vert = vert; |
| | } |
| |
|
| |
|
| |
|
| | |
| | static void mjc_initCCD(ccd_t* ccd, const mjModel* m) { |
| | CCD_INIT(ccd); |
| | ccd->mpr_tolerance = m->opt.ccd_tolerance; |
| | ccd->epa_tolerance = m->opt.ccd_tolerance; |
| | ccd->max_iterations = m->opt.ccd_iterations; |
| | } |
| |
|
| |
|
| |
|
| | |
| | static int mjc_CCDIteration(const mjModel* m, const mjData* d, mjCCDObj* obj1, mjCCDObj* obj2, |
| | mjContact* con, int max_contacts, mjtNum margin) { |
| | if (!mjDISABLED(mjDSBL_NATIVECCD)) { |
| | mjCCDConfig config; |
| | mjCCDStatus status; |
| |
|
| | |
| | config.max_iterations = m->opt.ccd_iterations; |
| | config.tolerance = m->opt.ccd_tolerance; |
| | config.max_contacts = max_contacts; |
| | config.dist_cutoff = 0; |
| | config.context = (void*)d; |
| | config.alloc = ccd_allocate; |
| | config.free = ccd_free; |
| |
|
| | mjtNum dist = mjc_ccd(&config, &status, obj1, obj2); |
| | if (dist < 0) { |
| | for (int i = 0; i < status.nx; i++) { |
| | mjContact* c = con++; |
| | c->dist = margin + dist; |
| | mju_sub3(c->frame, status.x1 + 3*i, status.x2 + 3*i); |
| | mju_normalize3(c->frame); |
| | c->pos[0] = 0.5 * (status.x1[0 + 3*i] + status.x2[0 + 3*i]); |
| | c->pos[1] = 0.5 * (status.x1[1 + 3*i] + status.x2[1 + 3*i]); |
| | c->pos[2] = 0.5 * (status.x1[2 + 3*i] + status.x2[2 + 3*i]); |
| | mju_zero3(c->frame+3); |
| | } |
| | return status.nx; |
| | } |
| | return 0; |
| | } |
| |
|
| | |
| | ccd_t ccd; |
| | mjc_initCCD(&ccd, m); |
| | ccd.first_dir = ccdFirstDirDefault; |
| | ccd.center1 = mjccd_center; |
| | ccd.center2 = mjccd_center; |
| | ccd.support1 = mjccd_support; |
| | ccd.support2 = mjccd_support; |
| |
|
| | ccd_vec3_t dir, pos; |
| | ccd_real_t depth; |
| |
|
| | |
| | if (ccdMPRPenetration(obj1, obj2, &ccd, &depth, &dir, &pos) == 0) { |
| | |
| | if (ccdVec3Eq(&dir, ccd_vec3_origin)) { |
| | return 0; |
| | } |
| |
|
| | |
| | con->dist = margin-depth; |
| | mju_copy3(con->frame, dir.v); |
| | mju_copy3(con->pos, pos.v); |
| | mju_zero3(con->frame+3); |
| |
|
| | |
| | if (obj1->geom >= 0 && obj2->geom >= 0) { |
| | mjc_fixNormal(m, d, con, obj1->geom, obj2->geom); |
| | } |
| |
|
| | return 1; |
| | } |
| | return 0; |
| | } |
| |
|
| |
|
| |
|
| | |
| | static int mjc_isDistinctContact(mjContact* con, int ncon, mjtNum tolerance) { |
| | for (int i=0; i < ncon-1; i++) { |
| | if (mju_dist3(con[i].pos, con[ncon - 1].pos) <= tolerance) { |
| | return 0; |
| | } |
| | } |
| | return 1; |
| | } |
| |
|
| |
|
| |
|
| | |
| | static void mju_rotateFrame(const mjtNum origin[3], const mjtNum rot[9], |
| | mjtNum xmat[9], mjtNum xpos[3]) { |
| | mjtNum mat[9], vec[3], rel[3]; |
| |
|
| | |
| | mju_mulMatMat3(mat, rot, xmat); |
| | mju_copy(xmat, mat, 9); |
| |
|
| | |
| | mju_sub3(rel, origin, xpos); |
| |
|
| | |
| | mju_mulMatVec3(vec, rot, rel); |
| | mju_subFrom3(vec, rel); |
| |
|
| | |
| | mju_subFrom3(xpos, vec); |
| | } |
| |
|
| |
|
| |
|
| | |
| | static int maxContacts(const mjCCDObj* obj1, const mjCCDObj* obj2) { |
| | const mjModel* m = obj1->model; |
| |
|
| | |
| | if (obj1->margin > 0 || obj2->margin > 0) { |
| | return 1; |
| | } |
| |
|
| | |
| | int type1 = m->geom_type[obj1->geom]; |
| | int type2 = m->geom_type[obj2->geom]; |
| | if (type1 == mjGEOM_BOX && type2 == mjGEOM_BOX) { |
| | return 8; |
| | } |
| |
|
| | |
| | if (type1 == mjGEOM_BOX || type1 == mjGEOM_MESH) { |
| | if (type2 == mjGEOM_BOX || type2 == mjGEOM_MESH) { |
| | return mjENABLED(mjENBL_MULTICCD) ? 4 : 1; |
| | } |
| | } |
| |
|
| | |
| | return 1; |
| | } |
| |
|
| |
|
| |
|
| | |
| | int mjc_Convex(const mjModel* m, const mjData* d, |
| | mjContact* con, int g1, int g2, mjtNum margin) { |
| | |
| | mjCCDObj obj1, obj2; |
| | mjc_initCCDObj(&obj1, m, d, g1, margin); |
| | mjc_initCCDObj(&obj2, m, d, g2, margin); |
| | int max_contacts = maxContacts(&obj1, &obj2); |
| |
|
| | |
| | int ncon = mjc_CCDIteration(m, d, &obj1, &obj2, con, max_contacts, margin); |
| |
|
| |
|
| | |
| | if (!mjDISABLED(mjDSBL_NATIVECCD) && max_contacts > 1) { |
| | return ncon; |
| | } |
| |
|
| | |
| | if (ncon == 1 && mjENABLED(mjENBL_MULTICCD) |
| | && m->geom_type[g1] != mjGEOM_ELLIPSOID && m->geom_type[g1] != mjGEOM_SPHERE |
| | && m->geom_type[g2] != mjGEOM_ELLIPSOID && m->geom_type[g2] != mjGEOM_SPHERE) { |
| | |
| | const mjtNum relative_tolerance = 1e-3; |
| | const mjtNum perturbation_angle = 1e-3; |
| |
|
| | |
| | mjtNum xpos1[3], xmat1[9], xpos2[3], xmat2[9]; |
| | mju_copy3(xpos1, d->geom_xpos+3*g1); |
| | mju_copy(xmat1, d->geom_xmat+9*g1, 9); |
| | mju_copy3(xpos2, d->geom_xpos+3*g2); |
| | mju_copy(xmat2, d->geom_xmat+9*g2, 9); |
| |
|
| | |
| | mjtNum frame[9]; |
| | mju_copy(frame, con[0].frame, 9); |
| | mju_makeFrame(frame); |
| |
|
| | |
| | const mjtNum tolerance = relative_tolerance * mju_min(m->geom_rbound[g1], m->geom_rbound[g2]); |
| |
|
| | |
| | mjtNum* axes[2] = {frame+3, frame+6}; |
| | mjtNum angles[2] = {-perturbation_angle, perturbation_angle}; |
| |
|
| | |
| | for (int axis_id = 0; axis_id < 2; ++axis_id) { |
| | for (int angle_id = 0; angle_id < 2; ++angle_id) { |
| | mjtNum* axis = axes[axis_id]; |
| | mjtNum angle = angles[angle_id]; |
| |
|
| | |
| | mjtNum quat[4], rot[9]; |
| | mju_axisAngle2Quat(quat, axis, angle); |
| | mju_quat2Mat(rot, quat); |
| |
|
| | |
| | mju_rotateFrame(con[0].pos, rot, d->geom_xmat+9*g1, d->geom_xpos+3*g1); |
| |
|
| | |
| | mjtNum invrot[9]; |
| | mju_transpose(invrot, rot, 3, 3); |
| | mju_rotateFrame(con[0].pos, invrot, d->geom_xmat+9*g2, d->geom_xpos+3*g2); |
| |
|
| | |
| | int new_contact = mjc_CCDIteration(m, d, &obj1, &obj2, con+ncon, 1, margin); |
| |
|
| | |
| | if (new_contact && mjc_isDistinctContact(con, ncon + 1, tolerance)) { |
| | |
| | con[ncon].dist = con[0].dist; |
| | |
| | ncon += 1; |
| | } |
| |
|
| | |
| | mju_copy3(d->geom_xpos+3*g1, xpos1); |
| | mju_copy(d->geom_xmat+9*g1, xmat1, 9); |
| | mju_copy3(d->geom_xpos+3*g2, xpos2); |
| | mju_copy(d->geom_xmat+9*g2, xmat2, 9); |
| | } |
| | } |
| | } |
| | return ncon; |
| | } |
| |
|
| |
|
| |
|
| | |
| | const int maxplanemesh = 3; |
| | const mjtNum tolplanemesh = 0.3; |
| |
|
| | |
| | static int addplanemesh(mjContact* con, const float vertex[3], |
| | const mjtNum pos1[3], const mjtNum normal1[3], |
| | const mjtNum pos2[3], const mjtNum mat2[9], |
| | const mjtNum first[3], mjtNum rbound) { |
| | |
| | mjtNum pnt[3], v[3] = {vertex[0], vertex[1], vertex[2]}; |
| | mju_mulMatVec3(pnt, mat2, v); |
| | mju_addTo3(pnt, pos2); |
| |
|
| | |
| | if (mju_dist3(pnt, first) < tolplanemesh*rbound) { |
| | return 0; |
| | } |
| |
|
| | |
| | mjtNum dif[3]; |
| | mju_sub3(dif, pnt, pos1); |
| |
|
| | |
| | con->dist = mju_dot3(normal1, dif); |
| |
|
| | |
| | mju_copy3(con->pos, pnt); |
| | mju_addToScl3(con->pos, normal1, -0.5*con->dist); |
| |
|
| | |
| | mju_copy3(con->frame, normal1); |
| | mju_zero3(con->frame+3); |
| |
|
| | return 1; |
| | } |
| |
|
| |
|
| |
|
| | |
| | int mjc_PlaneConvex(const mjModel* m, const mjData* d, |
| | mjContact* con, int g1, int g2, mjtNum margin) { |
| | mjGETINFO |
| | mjtNum dist, dif[3], normal[3] = {mat1[2], mat1[5], mat1[8]}; |
| | ccd_vec3_t dir, vec; |
| | mjCCDObj obj; |
| | mjc_initCCDObj(&obj, m, d, g2, 0); |
| | |
| | ccdVec3Set(&dir, -mat1[2], -mat1[5], -mat1[8]); |
| | mjccd_support(&obj, &dir, &vec); |
| |
|
| | |
| | mju_sub3(dif, vec.v, pos1); |
| | dist = mju_dot3(normal, dif); |
| | if (dist > margin) { |
| | return 0; |
| | } |
| |
|
| | |
| | con->dist = dist; |
| | mju_copy3(con->pos, vec.v); |
| | mju_addToScl3(con->pos, normal, -0.5*dist); |
| | mju_copy3(con->frame, normal); |
| | mju_zero3(con->frame+3); |
| |
|
| | |
| | float* vertdata; |
| | int graphadr, numvert, locid; |
| | int *vert_edgeadr, *vert_globalid, *edge_localid; |
| | mjtNum vdot; |
| | int count = 1, g = g2; |
| |
|
| | |
| | if (m->geom_dataid[g] == -1) { |
| | return count; |
| | } |
| |
|
| | |
| | vertdata = m->mesh_vert + 3*m->mesh_vertadr[m->geom_dataid[g]]; |
| |
|
| | |
| | mjtNum locdir[3]; |
| | mju_mulMatTVec3(locdir, d->geom_xmat+9*g, dir.v); |
| |
|
| | |
| | mju_sub3(dif, pos2, pos1); |
| | mjtNum threshold = mju_dot3(normal, dif) - margin; |
| |
|
| | |
| | if (m->mesh_graphadr[m->geom_dataid[g]] < 0) { |
| | |
| | for (int i=0; i < m->mesh_vertnum[m->geom_dataid[g]] && count < maxplanemesh; i++) { |
| | |
| | vdot = locdir[0] * (mjtNum)vertdata[3*i] + |
| | locdir[1] * (mjtNum)vertdata[3*i+1] + |
| | locdir[2] * (mjtNum)vertdata[3*i+2]; |
| |
|
| | |
| | if (vdot > threshold && i != obj.meshindex) { |
| | count += addplanemesh(con+count, vertdata+3*i, |
| | pos1, normal, pos2, mat2, |
| | con->pos, m->geom_rbound[g2]); |
| | } |
| | } |
| | } |
| |
|
| | |
| | else if (obj.meshindex >= 0) { |
| | |
| | graphadr = m->mesh_graphadr[m->geom_dataid[g]]; |
| | numvert = m->mesh_graph[graphadr]; |
| | vert_edgeadr = m->mesh_graph + graphadr + 2; |
| | vert_globalid = m->mesh_graph + graphadr + 2 + numvert; |
| | edge_localid = m->mesh_graph + graphadr + 2 + 2*numvert; |
| |
|
| | |
| | int i = vert_edgeadr[obj.meshindex]; |
| | while ((locid=edge_localid[i]) >= 0 && count < maxplanemesh) { |
| | |
| | vdot = locdir[0] * (mjtNum)vertdata[3*vert_globalid[locid]] + |
| | locdir[1] * (mjtNum)vertdata[3*vert_globalid[locid]+1] + |
| | locdir[2] * (mjtNum)vertdata[3*vert_globalid[locid]+2]; |
| |
|
| | |
| | if (vdot > threshold) { |
| | count += addplanemesh(con+count, vertdata+3*vert_globalid[locid], |
| | pos1, normal, pos2, mat2, |
| | con->pos, m->geom_rbound[g2]); |
| | } |
| |
|
| | |
| | i++; |
| | } |
| | } |
| |
|
| | return count; |
| | } |
| |
|
| |
|
| |
|
| | |
| |
|
| | |
| | static void prism_firstdir(const void* o1, const void* o2, ccd_vec3_t *vec) { |
| | ccdVec3Set(vec, 0, 0, 1); |
| | } |
| |
|
| |
|
| | |
| | static void addVert(int* nvert, mjCCDObj* obj, mjtNum x, mjtNum y, mjtNum z) { |
| | |
| | mju_copy3(obj->prism[0], obj->prism[1]); |
| | mju_copy3(obj->prism[1], obj->prism[2]); |
| | mju_copy3(obj->prism[3], obj->prism[4]); |
| | mju_copy3(obj->prism[4], obj->prism[5]); |
| |
|
| | |
| | obj->prism[2][0] = obj->prism[5][0] = x; |
| | obj->prism[2][1] = obj->prism[5][1] = y; |
| | obj->prism[5][2] = z; |
| |
|
| | |
| | (*nvert)++; |
| | } |
| |
|
| |
|
| |
|
| | |
| | int mjc_ConvexHField(const mjModel* m, const mjData* d, |
| | mjContact* con, int g1, int g2, mjtNum margin) { |
| | mjGETINFO_HFIELD |
| | mjtNum mat[9], savemat2[9], savepos2[3], pos[3], vec[3], r2, dx, dy; |
| | mjtNum xmin, xmax, ymin, ymax, zmin, zmax; |
| | int hid = m->geom_dataid[g1]; |
| | int nrow = m->hfield_nrow[hid]; |
| | int ncol = m->hfield_ncol[hid]; |
| | int dr[2], cnt, rmin, rmax, cmin, cmax; |
| | const float* data = m->hfield_data + m->hfield_adr[hid]; |
| |
|
| | |
| | mjCCDObj obj1, obj2; |
| | mjc_initCCDObj(&obj1, m, d, g1, 0); |
| | mjc_initCCDObj(&obj2, m, d, g2, 0); |
| |
|
| | ccd_vec3_t dirccd, vecccd; |
| | ccd_real_t depth; |
| | ccd_t ccd; |
| |
|
| | |
| | size1 = m->hfield_size + 4*hid; |
| |
|
| | |
| |
|
| | |
| | mju_sub3(vec, pos2, pos1); |
| | mju_mulMatTVec(pos, mat1, vec, 3, 3); |
| |
|
| | |
| | r2 = m->geom_rbound[g2]; |
| |
|
| | |
| | for (int i=0; i < 2; i++) { |
| | if ((size1[i] < pos[i]-r2-margin) || (-size1[i] > pos[i]+r2+margin)) { |
| | return 0; |
| | } |
| | } |
| |
|
| | |
| | if (size1[2] < pos[2]-r2-margin) { |
| | return 0; |
| | } |
| | if (-size1[3] > pos[2]+r2+margin) { |
| | return 0; |
| | } |
| |
|
| | |
| | mju_mulMatTMat3(mat, mat1, mat2); |
| |
|
| | |
| |
|
| | |
| | mju_copy(savemat2, mat2, 9); |
| | mju_copy3(savepos2, pos2); |
| | mju_copy(mat2, mat, 9); |
| | mju_copy3(pos2, pos); |
| |
|
| | |
| | ccdVec3Set(&dirccd, 1, 0, 0); |
| | mjccd_support(&obj2, &dirccd, &vecccd); |
| | xmax = vecccd.v[0]; |
| |
|
| | |
| | ccdVec3Set(&dirccd, -1, 0, 0); |
| | mjccd_support(&obj2, &dirccd, &vecccd); |
| | xmin = vecccd.v[0]; |
| |
|
| | |
| | ccdVec3Set(&dirccd, 0, 1, 0); |
| | mjccd_support(&obj2, &dirccd, &vecccd); |
| | ymax = vecccd.v[1]; |
| |
|
| | |
| | ccdVec3Set(&dirccd, 0, -1, 0); |
| | mjccd_support(&obj2, &dirccd, &vecccd); |
| | ymin = vecccd.v[1]; |
| |
|
| | |
| | ccdVec3Set(&dirccd, 0, 0, 1); |
| | mjccd_support(&obj2, &dirccd, &vecccd); |
| | zmax = vecccd.v[2]; |
| |
|
| | |
| | ccdVec3Set(&dirccd, 0, 0, -1); |
| | mjccd_support(&obj2, &dirccd, &vecccd); |
| | zmin = vecccd.v[2]; |
| |
|
| | |
| | if ((xmin-margin > size1[0]) || (xmax+margin < -size1[0]) || |
| | (ymin-margin > size1[1]) || (ymax+margin < -size1[1]) || |
| | (zmin-margin > size1[2]) || (zmax+margin < -size1[3])) { |
| | |
| | mju_copy(mat2, savemat2, 9); |
| | mju_copy3(pos2, savepos2); |
| |
|
| | return 0; |
| | } |
| |
|
| | |
| | cmin = (int) mju_floor((xmin + size1[0]) / (2*size1[0]) * (ncol-1)); |
| | cmax = (int) mju_ceil ((xmax + size1[0]) / (2*size1[0]) * (ncol-1)); |
| | rmin = (int) mju_floor((ymin + size1[1]) / (2*size1[1]) * (nrow-1)); |
| | rmax = (int) mju_ceil ((ymax + size1[1]) / (2*size1[1]) * (nrow-1)); |
| | cmin = mjMAX(0, cmin); |
| | cmax = mjMIN(ncol-1, cmax); |
| | rmin = mjMAX(0, rmin); |
| | rmax = mjMIN(nrow-1, rmax); |
| |
|
| | |
| |
|
| | |
| | mjc_initCCD(&ccd, m); |
| | ccd.first_dir = prism_firstdir; |
| | ccd.center1 = mjccd_prism_center; |
| | ccd.center2 = mjccd_center; |
| | ccd.support1 = mjccd_prism_support; |
| | ccd.support2 = mjccd_support; |
| |
|
| | |
| | obj2.margin = margin; |
| |
|
| | |
| | dx = (2.0*size1[0]) / (ncol-1); |
| | dy = (2.0*size1[1]) / (nrow-1); |
| | dr[0] = 1; |
| | dr[1] = 0; |
| |
|
| | |
| | obj1.prism[0][2] = obj1.prism[1][2] = obj1.prism[2][2] = -size1[3]; |
| |
|
| | |
| | cnt = 0; |
| | for (int r=rmin; r < rmax; r++) { |
| | int nvert = 0; |
| | for (int c=cmin; c <= cmax; c++) { |
| | for (int i=0; i < 2; i++) { |
| | |
| | addVert(&nvert, &obj1, dx*c-size1[0], dy*(r+dr[i])-size1[1], |
| | data[(r+dr[i])*ncol+c]*size1[2]+margin); |
| |
|
| | |
| | if (nvert > 2) { |
| | |
| | if (obj1.prism[3][2] < zmin && obj1.prism[4][2] < zmin |
| | && obj1.prism[5][2] < zmin) { |
| | continue; |
| | } |
| |
|
| | |
| | if (mjc_penetration(m, &obj1, &obj2, &ccd, &depth, &dirccd, &vecccd) == 0 |
| | && !ccdVec3Eq(&dirccd, ccd_vec3_origin)) { |
| | |
| | con[cnt].dist = -depth; |
| | mju_mulMatVec3(con[cnt].frame, mat1, dirccd.v); |
| | mju_mulMatVec3(con[cnt].pos, mat1, vecccd.v); |
| | mju_addTo3(con[cnt].pos, pos1); |
| | mju_zero3(con[cnt].frame+3); |
| |
|
| | |
| | cnt++; |
| | if (cnt >= mjMAXCONPAIR) { |
| | r = rmax+1; |
| | c = cmax+1; |
| | i = 3; |
| | break; |
| | } |
| | } |
| | } |
| | } |
| | } |
| | } |
| |
|
| | |
| | mju_copy(mat2, savemat2, 9); |
| | mju_copy3(pos2, savepos2); |
| |
|
| | |
| | for (int i=0; i < cnt; i++) { |
| | mjc_fixNormal(m, d, con+i, g1, g2); |
| | } |
| |
|
| | return cnt; |
| | } |
| |
|
| |
|
| |
|
| | |
| |
|
| | |
| | static int mjc_ellipsoidInside(mjtNum nrm[3], const mjtNum pos[3], const mjtNum size[3]) { |
| | |
| | const int maxiter = 30; |
| | const mjtNum tolerance = 1e-6; |
| |
|
| | |
| | mjtNum S2inv[3] = {1/(size[0]*size[0]), 1/(size[1]*size[1]), 1/(size[2]*size[2])}; |
| | mjtNum C = pos[0]*pos[0]*S2inv[0] + pos[1]*pos[1]*S2inv[1] + pos[2]*pos[2]*S2inv[2] - 1; |
| | if (C > 0) { |
| | return 0; |
| | } |
| |
|
| | |
| | mju_normalize3(nrm); |
| |
|
| | |
| | int iter; |
| | for (iter=0; iter < maxiter; iter++) { |
| | |
| | mjtNum A = nrm[0]*nrm[0]*S2inv[0] + nrm[1]*nrm[1]*S2inv[1] + nrm[2]*nrm[2]*S2inv[2]; |
| | mjtNum B = pos[0]*nrm[0]*S2inv[0] + pos[1]*nrm[1]*S2inv[1] + pos[2]*nrm[2]*S2inv[2]; |
| | mjtNum det = B*B - A*C; |
| | if (det < mjMINVAL || A < mjMINVAL) { |
| | return (iter > 0); |
| | } |
| |
|
| | |
| | mjtNum x = (-B + mju_sqrt(det))/A; |
| | if (x < 0) { |
| | return (iter > 0); |
| | } |
| |
|
| | |
| | mjtNum pnt[3]; |
| | mju_addScl3(pnt, pos, nrm, x); |
| |
|
| | |
| | mjtNum newnrm[3] = {pnt[0]*S2inv[0], pnt[1]*S2inv[1], pnt[2]*S2inv[2]}; |
| | mju_normalize3(newnrm); |
| |
|
| | |
| | mjtNum change = mju_dist3(nrm, newnrm); |
| | mju_copy3(nrm, newnrm); |
| |
|
| | |
| | if (change < tolerance) { |
| | break; |
| | } |
| | } |
| |
|
| | return 1; |
| | } |
| |
|
| |
|
| |
|
| | |
| | static int mjc_ellipsoidOutside(mjtNum nrm[3], const mjtNum pos[3], const mjtNum size[3]) { |
| | |
| | const int maxiter = 30; |
| | const mjtNum tolerance = 1e-6; |
| |
|
| | |
| | mjtNum S2[3] = {size[0]*size[0], size[1]*size[1], size[2]*size[2]}; |
| | mjtNum PS2[3] = {pos[0]*pos[0]*S2[0], pos[1]*pos[1]*S2[1], pos[2]*pos[2]*S2[2]}; |
| |
|
| | |
| | mjtNum la = 0; |
| | int iter; |
| | for (iter=0; iter < maxiter; iter++) { |
| | |
| | mjtNum R[3] = {1/(S2[0]+la), 1/(S2[1]+la), 1/(S2[2]+la)}; |
| |
|
| | |
| | mjtNum val = PS2[0]*R[0]*R[0] + PS2[1]*R[1]*R[1] + PS2[2]*R[2]*R[2] - 1; |
| | if (val < tolerance) { |
| | break; |
| | } |
| |
|
| | |
| | mjtNum deriv = -2*(PS2[0]*R[0]*R[0]*R[0] + PS2[1]*R[1]*R[1]*R[1] + PS2[2]*R[2]*R[2]*R[2]); |
| | if (deriv > -mjMINVAL) { |
| | break; |
| | } |
| |
|
| | |
| | mjtNum delta = -val/deriv; |
| | if (delta < tolerance) { |
| | break; |
| | } |
| |
|
| | |
| | la += delta; |
| | } |
| |
|
| | |
| | nrm[0] = pos[0]/(S2[0]+la); |
| | nrm[1] = pos[1]/(S2[1]+la); |
| | nrm[2] = pos[2]/(S2[2]+la); |
| | mju_normalize3(nrm); |
| |
|
| | return 1; |
| | } |
| |
|
| |
|
| |
|
| | |
| | void mjc_fixNormal(const mjModel* m, const mjData* d, mjContact* con, int g1, int g2) { |
| | mjtNum dst1, dst2; |
| |
|
| | |
| | int gid[2] = {g1, g2}; |
| | mjtGeom type[2]; |
| | for (int i=0; i < 2; i++) { |
| | type[i] = m->geom_type[gid[i]]; |
| |
|
| | |
| | if (type[i] != mjGEOM_SPHERE && |
| | type[i] != mjGEOM_CAPSULE && |
| | type[i] != mjGEOM_ELLIPSOID && |
| | type[i] != mjGEOM_CYLINDER) { |
| | type[i] = mjGEOM_NONE; |
| | } |
| | } |
| |
|
| | |
| | if (type[0] == mjGEOM_NONE && type[1] == mjGEOM_NONE) { |
| | return; |
| | } |
| |
|
| | |
| | mjtNum normal[2][3] = { |
| | {con->frame[0], con->frame[1], con->frame[2]}, |
| | {-con->frame[0], -con->frame[1], -con->frame[2]} |
| | }; |
| |
|
| | |
| | int processed[2] = {0, 0}; |
| | for (int i=0; i < 2; i++) { |
| | if (type[i] != mjGEOM_NONE) { |
| | |
| | mjtNum* mat = d->geom_xmat + 9*gid[i]; |
| | mjtNum* size = m->geom_size + 3*gid[i]; |
| |
|
| | |
| | mjtNum dif[3], pos[3], nrm[3]; |
| | mju_sub3(dif, con->pos, d->geom_xpos+3*gid[i]); |
| | mju_mulMatTVec3(pos, mat, dif); |
| | mju_mulMatTVec3(nrm, mat, normal[i]); |
| |
|
| | |
| | switch (type[i]) { |
| | case mjGEOM_SPHERE: |
| | mju_copy3(nrm, pos); |
| | processed[i] = 1; |
| | break; |
| |
|
| | case mjGEOM_CAPSULE: |
| | |
| | if (pos[2] < -size[1]) { |
| | nrm[2] = pos[2]+size[1]; |
| | } |
| |
|
| | |
| | else if (pos[2] > size[1]) { |
| | nrm[2] = pos[2]-size[1]; |
| | } |
| |
|
| | |
| | else { |
| | nrm[2] = 0; |
| | } |
| |
|
| | |
| | nrm[0] = pos[0]; |
| | nrm[1] = pos[1]; |
| | processed[i] = 1; |
| | break; |
| |
|
| | case mjGEOM_ELLIPSOID: |
| | |
| | if (size[0] < mjMINVAL || size[1] < mjMINVAL || size[2] < mjMINVAL) { |
| | break; |
| | } |
| |
|
| | |
| | dst1 = pos[0]*pos[0]/(size[0]*size[0]) + |
| | pos[1]*pos[1]/(size[1]*size[1]) + |
| | pos[2]*pos[2]/(size[2]*size[2]); |
| |
|
| | |
| | if (dst1 <= 1) { |
| | processed[i] = mjc_ellipsoidInside(nrm, pos, size); |
| | } else { |
| | processed[i] = mjc_ellipsoidOutside(nrm, pos, size); |
| | } |
| | break; |
| |
|
| | case mjGEOM_CYLINDER: |
| | |
| | if (mju_abs(pos[2]) > 0.95*size[1]) { |
| | break; |
| | } |
| |
|
| | |
| | dst1 = mju_abs(size[1]-mju_abs(pos[2])); |
| | dst2 = mju_abs(size[0]-mju_norm(pos, 2)); |
| |
|
| | |
| | if (dst1 < 0.25*dst2) { |
| | break; |
| | } |
| |
|
| | |
| | nrm[0] = pos[0]; |
| | nrm[1] = pos[1]; |
| | nrm[2] = 0; |
| | processed[i] = 1; |
| | break; |
| | default: |
| | |
| | break; |
| | } |
| |
|
| | |
| | if (processed[i]) { |
| | mju_normalize3(nrm); |
| | mju_mulMatVec3(normal[i], mat, nrm); |
| | } |
| | } |
| | } |
| |
|
| | |
| | if (processed[0] && processed[1]) { |
| | mju_sub3(con->frame, normal[0], normal[1]); |
| | mju_normalize3(con->frame); |
| | } |
| |
|
| | |
| | else if (processed[0]) { |
| | mju_copy3(con->frame, normal[0]); |
| | } |
| |
|
| | |
| | else if (processed[1]) { |
| | mju_scl3(con->frame, normal[1], -1); |
| | } |
| |
|
| | |
| | if (processed[0] || processed[1]) { |
| | mju_zero3(con->frame+3); |
| | } |
| | } |
| |
|
| |
|
| |
|
| | |
| |
|
| | |
| | int mjc_ConvexElem(const mjModel* m, const mjData* d, mjContact* con, |
| | int g1, int f1, int e1, int v1, int f2, int e2, mjtNum margin) { |
| | mjCCDObj obj1, obj2; |
| | mjc_initCCDObj(&obj1, m, d, g1, margin); |
| | mjc_initCCDObj(&obj2, m, d, -1, margin); |
| | mjc_setCCDObjFlex(&obj1, f1, e1, v1); |
| | mjc_setCCDObjFlex(&obj2, f2, e2, -1); |
| |
|
| | |
| | return mjc_CCDIteration(m, d, &obj1, &obj2, con, 1, margin); |
| | } |
| |
|
| |
|
| |
|
| | |
| | int mjc_HFieldElem(const mjModel* m, const mjData* d, mjContact* con, |
| | int g, int f, int e, mjtNum margin) { |
| | mjtNum vec[3], dx, dy; |
| | mjtNum xmin, xmax, ymin, ymax, zmin, zmax; |
| | int dr[2], cnt, rmin, rmax, cmin, cmax; |
| | mjCCDObj obj1; |
| | obj1.center = mjc_prism_center; |
| | obj1.support = mjc_prism_support; |
| |
|
| | |
| | int hid = m->geom_dataid[g]; |
| | int nrow = m->hfield_nrow[hid]; |
| | int ncol = m->hfield_ncol[hid]; |
| | mjtNum* hpos = d->geom_xpos + 3*g; |
| | mjtNum* hmat = d->geom_xmat + 9*g; |
| | mjtNum* hsize = m->hfield_size + 4*hid; |
| | const float* hdata = m->hfield_data + m->hfield_adr[hid]; |
| |
|
| | |
| | int dim = m->flex_dim[f]; |
| | const int* edata = m->flex_elem + m->flex_elemdataadr[f] + e*(dim+1); |
| | mjtNum* evert[4] = {NULL, NULL, NULL, NULL}; |
| | for (int i=0; i <= dim; i++) { |
| | evert[i] = d->flexvert_xpos + 3*(m->flex_vertadr[f] + edata[i]); |
| | } |
| | mjtNum* ecenter = d->flexelem_aabb + 6*(m->flex_elemadr[f]+e); |
| |
|
| | |
| | ccd_vec3_t dirccd, vecccd; |
| | ccd_real_t depth; |
| | mjCCDObj obj2; |
| | mjc_initCCDObj(&obj2, m, d, -1, margin); |
| | mjc_setCCDObjFlex(&obj2, f, e, -1); |
| | ccd_t ccd; |
| |
|
| | |
| |
|
| | |
| | mjtNum savevert[4][3]; |
| | for (int i=0; i <= dim; i++) { |
| | mju_copy3(savevert[i], evert[i]); |
| | mju_sub3(vec, evert[i], hpos); |
| | mju_mulMatTVec(evert[i], hmat, vec, 3, 3); |
| | } |
| |
|
| | |
| | mjtNum savecenter[3]; |
| | mju_copy3(savecenter, ecenter); |
| | mju_sub3(vec, ecenter, hpos); |
| | mju_mulMatTVec(ecenter, hmat, vec, 3, 3); |
| |
|
| | |
| | xmin = xmax = evert[0][0]; |
| | ymin = ymax = evert[0][1]; |
| | zmin = zmax = evert[0][2]; |
| | for (int i=1; i <= dim; i++) { |
| | xmin = mju_min(xmin, evert[i][0]); |
| | xmax = mju_max(xmax, evert[i][0]); |
| | ymin = mju_min(ymin, evert[i][1]); |
| | ymax = mju_max(ymax, evert[i][1]); |
| | zmin = mju_min(zmin, evert[i][2]); |
| | zmax = mju_max(zmax, evert[i][2]); |
| | } |
| |
|
| | |
| | if ((xmin-margin > hsize[0]) || (xmax+margin < -hsize[0]) || |
| | (ymin-margin > hsize[1]) || (ymax+margin < -hsize[1]) || |
| | (zmin-margin > hsize[2]) || (zmax+margin < -hsize[3])) { |
| | |
| | for (int i=0; i <= dim; i++) { |
| | mju_copy3(evert[i], savevert[i]); |
| | } |
| | mju_copy3(ecenter, savecenter); |
| |
|
| | return 0; |
| | } |
| |
|
| | |
| | cmin = (int) mju_floor((xmin + hsize[0]) / (2*hsize[0]) * (ncol-1)); |
| | cmax = (int) mju_ceil ((xmax + hsize[0]) / (2*hsize[0]) * (ncol-1)); |
| | rmin = (int) mju_floor((ymin + hsize[1]) / (2*hsize[1]) * (nrow-1)); |
| | rmax = (int) mju_ceil ((ymax + hsize[1]) / (2*hsize[1]) * (nrow-1)); |
| | cmin = mjMAX(0, cmin); |
| | cmax = mjMIN(ncol-1, cmax); |
| | rmin = mjMAX(0, rmin); |
| | rmax = mjMIN(nrow-1, rmax); |
| |
|
| | |
| |
|
| | |
| | CCD_INIT(&ccd); |
| | ccd.first_dir = prism_firstdir; |
| | ccd.center1 = mjccd_prism_center; |
| | ccd.center2 = mjccd_center; |
| | ccd.support1 = mjccd_prism_support; |
| | ccd.support2 = mjccd_support; |
| |
|
| | |
| | ccd.max_iterations = m->opt.ccd_iterations; |
| | ccd.mpr_tolerance = m->opt.ccd_tolerance; |
| |
|
| | |
| | dx = (2.0*hsize[0]) / (ncol-1); |
| | dy = (2.0*hsize[1]) / (nrow-1); |
| | dr[0] = 1; |
| | dr[1] = 0; |
| |
|
| | |
| | obj1.prism[0][2] = obj1.prism[1][2] = obj1.prism[2][2] = -hsize[3]; |
| |
|
| | |
| | cnt = 0; |
| | for (int r=rmin; r < rmax; r++) { |
| | int nvert = 0; |
| | for (int c=cmin; c <= cmax; c++) { |
| | for (int k=0; k < 2; k++) { |
| | |
| | addVert(&nvert, &obj1, dx*c-hsize[0], dy*(r+dr[k])-hsize[1], |
| | hdata[(r+dr[k])*ncol+c]*hsize[2]+margin); |
| |
|
| | |
| | if (nvert > 2) { |
| | |
| | if (obj1.prism[3][2] < zmin && obj1.prism[4][2] < zmin && obj1.prism[5][2] < zmin) { |
| | continue; |
| | } |
| |
|
| | |
| | if (mjc_penetration(m, &obj1, &obj2, &ccd, &depth, &dirccd, &vecccd) == 0) { |
| | if (!ccdVec3Eq(&dirccd, ccd_vec3_origin)) { |
| | |
| | con[cnt].dist = -depth; |
| | mju_mulMatVec3(con[cnt].frame, hmat, dirccd.v); |
| | mju_mulMatVec3(con[cnt].pos, hmat, vecccd.v); |
| | mju_addTo3(con[cnt].pos, hpos); |
| | mju_zero3(con[cnt].frame+3); |
| |
|
| | |
| | cnt++; |
| | if (cnt >= mjMAXCONPAIR) { |
| | r = rmax+1; |
| | c = cmax+1; |
| | k = 3; |
| | break; |
| | } |
| | } |
| | } |
| | } |
| | } |
| | } |
| | } |
| |
|
| | |
| | for (int i=0; i <= dim; i++) { |
| | mju_copy3(evert[i], savevert[i]); |
| | } |
| | mju_copy3(ecenter, savecenter); |
| |
|
| | return cnt; |
| | } |
| |
|