| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| |
|
| | #include "engine/engine_collision_primitive.h" |
| |
|
| | #include <mujoco/mjdata.h> |
| | #include <mujoco/mjmacro.h> |
| | #include <mujoco/mjmodel.h> |
| | #include "engine/engine_util_blas.h" |
| | #include "engine/engine_util_misc.h" |
| | #include "engine/engine_util_spatial.h" |
| |
|
| |
|
| | |
| |
|
| | |
| | static int mjraw_PlaneSphere(mjContact* con, mjtNum margin, |
| | const mjtNum* pos1, const mjtNum* mat1, const mjtNum* size1, |
| | const mjtNum* pos2, const mjtNum* mat2, const mjtNum* size2) { |
| | |
| | con[0].frame[0] = mat1[2]; |
| | con[0].frame[1] = mat1[5]; |
| | con[0].frame[2] = mat1[8]; |
| |
|
| | |
| | mjtNum tmp[3] = {pos2[0] - pos1[0], pos2[1] - pos1[1], pos2[2] - pos1[2]}; |
| | mjtNum cdist = mju_dot3(tmp, con[0].frame); |
| | if (cdist > margin + size2[0]) { |
| | return 0; |
| | } |
| |
|
| | |
| | con[0].dist = cdist - size2[0]; |
| | mju_scl3(tmp, con[0].frame, -con[0].dist/2 - size2[0]); |
| | mju_add3(con[0].pos, pos2, tmp); |
| |
|
| | mju_zero3(con[0].frame+3); |
| | return 1; |
| | } |
| |
|
| |
|
| |
|
| | |
| | int mjc_PlaneSphere(const mjModel* m, const mjData* d, |
| | mjContact* con, int g1, int g2, mjtNum margin) { |
| | mjGETINFO |
| | return mjraw_PlaneSphere(con, margin, pos1, mat1, size1, pos2, mat2, size2); |
| | } |
| |
|
| |
|
| |
|
| | |
| | int mjc_PlaneCapsule(const mjModel* m, const mjData* d, |
| | mjContact* con, int g1, int g2, mjtNum margin) { |
| | mjGETINFO |
| |
|
| | |
| | mjtNum axis[3] = {mat2[2], mat2[5], mat2[8]}; |
| | mjtNum segment[3] = {size2[1]*axis[0], size2[1]*axis[1], size2[1]*axis[2]}; |
| |
|
| | |
| | mjtNum pos[3]; |
| | mju_add3(pos, pos2, segment); |
| | int n1 = mjraw_PlaneSphere(con, margin, pos1, mat1, size1, pos, mat2, size2); |
| |
|
| | |
| | mju_sub3(pos, pos2, segment); |
| | int n2 = mjraw_PlaneSphere(con+n1, margin, pos1, mat1, size1, pos, mat2, size2); |
| |
|
| | |
| | if (n1) { |
| | mju_copy3(con->frame+3, axis); |
| | } |
| | if (n2) { |
| | mju_copy3((con+n1)->frame+3, axis); |
| | } |
| |
|
| | return n1+n2; |
| | } |
| |
|
| |
|
| |
|
| | |
| | int mjc_PlaneCylinder(const mjModel* m, const mjData* d, |
| | mjContact* con, int g1, int g2, mjtNum margin) { |
| | mjGETINFO |
| | mjtNum normal[3] = {mat1[2], mat1[5], mat1[8]}; |
| | mjtNum axis[3] = {mat2[2], mat2[5], mat2[8]}; |
| |
|
| | |
| | mjtNum prjaxis = mju_dot3(normal, axis); |
| | if (prjaxis > 0) { |
| | mju_scl3(axis, axis, -1); |
| | prjaxis = -prjaxis; |
| | } |
| |
|
| | |
| | mjtNum vec[3] = {pos2[0] - pos1[0], pos2[1] - pos1[1], pos2[2] - pos1[2]}; |
| | mjtNum dist0 = mju_dot3(vec, normal); |
| |
|
| | |
| | mju_scl3(vec, axis, prjaxis); |
| | mju_subFrom3(vec, normal); |
| | mjtNum len_sqr = mju_dot3(vec, vec); |
| |
|
| | |
| | if (len_sqr >= mjMINVAL*mjMINVAL) { |
| | mjtNum scl = size2[0]/mju_sqrt(len_sqr); |
| | vec[0] *= scl; |
| | vec[1] *= scl; |
| | vec[2] *= scl; |
| | } |
| |
|
| | |
| | else { |
| | vec[0] = mat2[0]*size2[0]; |
| | vec[1] = mat2[3]*size2[0]; |
| | vec[2] = mat2[6]*size2[0]; |
| | } |
| |
|
| | |
| | mjtNum prjvec = mju_dot3(vec, normal); |
| |
|
| | |
| | mju_scl3(axis, axis, size2[1]); |
| | prjaxis *= size2[1]; |
| |
|
| | |
| | int cnt = 0; |
| | if (dist0 + prjaxis + prjvec <= margin) { |
| | con[cnt].dist = dist0 + prjaxis + prjvec; |
| | mju_add3(con[cnt].pos, pos2, vec); |
| | mju_addTo3(con[cnt].pos, axis); |
| | mju_addToScl3(con[cnt].pos, normal, -con[cnt].dist*0.5); |
| | mju_copy3(con[cnt].frame, normal); |
| | mju_zero3(con[cnt].frame+3); |
| | cnt++; |
| | } else { |
| | return 0; |
| | } |
| |
|
| | |
| | if (dist0 - prjaxis + prjvec <= margin) { |
| | con[cnt].dist = dist0 - prjaxis + prjvec; |
| | mju_add3(con[cnt].pos, pos2, vec); |
| | mju_subFrom3(con[cnt].pos, axis); |
| | mju_addToScl3(con[cnt].pos, normal, -con[cnt].dist*0.5); |
| | mju_copy3(con[cnt].frame, normal); |
| | mju_zero3(con[cnt].frame+3); |
| | cnt++; |
| | } |
| |
|
| | |
| | mjtNum prjvec1 = -prjvec*0.5; |
| | if (dist0 + prjaxis + prjvec1 <= margin) { |
| | |
| | mjtNum vec1[3]; |
| | mju_cross(vec1, vec, axis); |
| | mju_normalize3(vec1); |
| | mju_scl3(vec1, vec1, size2[0]*mju_sqrt(3.0)/2); |
| |
|
| | |
| | con[cnt].dist = dist0 + prjaxis + prjvec1; |
| | mju_add3(con[cnt].pos, pos2, vec1); |
| | mju_addTo3(con[cnt].pos, axis); |
| | mju_addToScl3(con[cnt].pos, vec, -0.5); |
| | mju_addToScl3(con[cnt].pos, normal, -con[cnt].dist*0.5); |
| | mju_copy3(con[cnt].frame, normal); |
| | mju_zero3(con[cnt].frame+3); |
| | cnt++; |
| |
|
| | |
| | con[cnt].dist = dist0 + prjaxis + prjvec1; |
| | mju_sub3(con[cnt].pos, pos2, vec1); |
| | mju_addTo3(con[cnt].pos, axis); |
| | mju_addToScl3(con[cnt].pos, vec, -0.5); |
| | mju_addToScl3(con[cnt].pos, normal, -con[cnt].dist*0.5); |
| | mju_copy3(con[cnt].frame, normal); |
| | mju_zero3(con[cnt].frame+3); |
| | cnt++; |
| | } |
| |
|
| | return cnt; |
| | } |
| |
|
| |
|
| |
|
| | |
| | int mjc_PlaneBox(const mjModel* m, const mjData* d, |
| | mjContact* con, int g1, int g2, mjtNum margin) { |
| | mjGETINFO |
| |
|
| | |
| | mjtNum norm[3] = {mat1[2], mat1[5], mat1[8]}; |
| | mjtNum dif[3] = {pos2[0] - pos1[0], pos2[1] - pos1[1], pos2[2] - pos1[2]}; |
| | mjtNum dist = mju_dot3(dif, norm); |
| |
|
| | |
| | int cnt = 0; |
| | for (int i=0; i < 8; i++) { |
| | |
| | mjtNum vec[3]; |
| | vec[0] = (i&1 ? size2[0] : -size2[0]); |
| | vec[1] = (i&2 ? size2[1] : -size2[1]); |
| | vec[2] = (i&4 ? size2[2] : -size2[2]); |
| |
|
| | |
| | mjtNum corner[3]; |
| | mju_mulMatVec3(corner, mat2, vec); |
| |
|
| | |
| | mjtNum ldist = mju_dot3(norm, corner); |
| | if (dist + ldist > margin || ldist > 0) { |
| | continue; |
| | } |
| |
|
| | |
| | con[cnt].dist = dist + ldist; |
| | mju_copy3(con[cnt].frame, norm); |
| | mju_zero3(con[cnt].frame+3); |
| | mju_addTo3(corner, pos2); |
| | mju_scl3(vec, norm, -con[cnt].dist/2); |
| | mju_add3(con[cnt].pos, corner, vec); |
| |
|
| | |
| | if (++cnt >= 4) { |
| | return 4; |
| | } |
| | } |
| |
|
| | return cnt; |
| | } |
| |
|
| |
|
| |
|
| | |
| |
|
| | |
| | static int mjraw_SphereSphere(mjContact* con, mjtNum margin, |
| | const mjtNum* pos1, const mjtNum* mat1, const mjtNum* size1, |
| | const mjtNum* pos2, const mjtNum* mat2, const mjtNum* size2) { |
| | |
| | mjtNum dif[3] = {pos1[0] - pos2[0], pos1[1] - pos2[1], pos1[2] - pos2[2]}; |
| | mjtNum cdist_sqr = mju_dot3(dif, dif); |
| | mjtNum min_dist = margin + size1[0] + size2[0]; |
| | if (cdist_sqr > min_dist*min_dist) { |
| | return 0; |
| | } |
| |
|
| | |
| | con[0].dist = mju_sqrt(cdist_sqr) - size1[0] - size2[0]; |
| | mju_sub3(con[0].frame, pos2, pos1); |
| | mjtNum len = mju_normalize3(con[0].frame); |
| |
|
| | |
| | |
| | if (len < mjMINVAL) { |
| | mjtNum axis1[3] = {mat1[2], mat1[5], mat1[8]}; |
| | mjtNum axis2[3] = {mat2[2], mat2[5], mat2[8]}; |
| | mju_cross(con[0].frame, axis1, axis2); |
| | mju_normalize3(con[0].frame); |
| | } |
| |
|
| | |
| | mju_scl3(con[0].pos, con[0].frame, size1[0] + con[0].dist/2); |
| | mju_addTo3(con[0].pos, pos1); |
| |
|
| | mju_zero3(con[0].frame+3); |
| | return 1; |
| | } |
| |
|
| |
|
| |
|
| | |
| | int mjc_SphereSphere(const mjModel* m, const mjData* d, |
| | mjContact* con, int g1, int g2, mjtNum margin) { |
| | mjGETINFO |
| | return mjraw_SphereSphere(con, margin, pos1, mat1, size1, pos2, mat2, size2); |
| | } |
| |
|
| |
|
| |
|
| | |
| | int mjraw_SphereCapsule(mjContact* con, mjtNum margin, |
| | const mjtNum* pos1, const mjtNum* mat1, const mjtNum* size1, |
| | const mjtNum* pos2, const mjtNum* mat2, const mjtNum* size2) { |
| | |
| | mjtNum len = size2[1]; |
| | mjtNum axis[3] = {mat2[2], mat2[5], mat2[8]}; |
| |
|
| | |
| | mjtNum vec[3] = {pos1[0] - pos2[0], pos1[1] - pos2[1], pos1[2] - pos2[2]}; |
| | mjtNum x = mju_clip(mju_dot3(axis, vec), -len, len); |
| |
|
| | |
| | mju_scl3(vec, axis, x); |
| | mju_addTo3(vec, pos2); |
| | return mjraw_SphereSphere(con, margin, pos1, mat1, size1, vec, mat2, size2); |
| | } |
| |
|
| |
|
| |
|
| | |
| | int mjc_SphereCapsule(const mjModel* m, const mjData* d, |
| | mjContact* con, int g1, int g2, mjtNum margin) { |
| | mjGETINFO |
| | return mjraw_SphereCapsule(con, margin, pos1, mat1, size1, pos2, mat2, size2); |
| | } |
| |
|
| |
|
| |
|
| | |
| | int mjc_SphereCylinder(const mjModel* m, const mjData* d, |
| | mjContact* con, int g1, int g2, mjtNum margin) { |
| | mjGETINFO |
| |
|
| | |
| | mjtNum radius = size2[0]; |
| | mjtNum height = size2[1]; |
| | mjtNum axis[3] = {mat2[2], mat2[5], mat2[8]}; |
| |
|
| | |
| | mjtNum vec[3] = {pos1[0] - pos2[0], pos1[1] - pos2[1], pos1[2] - pos2[2]}; |
| | mjtNum x = mju_dot3(axis, vec); |
| | mjtNum a_proj[3], p_proj[3]; |
| | mju_scl3(a_proj, axis, x); |
| | mju_sub3(p_proj, vec, a_proj); |
| | mjtNum p_proj_sqr = mju_dot3(p_proj, p_proj); |
| |
|
| | |
| | int collide_side = mju_abs(x) < height; |
| | int collide_cap = p_proj_sqr < radius*radius; |
| | if (collide_side && collide_cap) { |
| | mjtNum dist_cap = height - mju_abs(x); |
| | mjtNum dist_radius = radius - mju_sqrt(p_proj_sqr); |
| | if (dist_cap < dist_radius) { |
| | collide_side = 0; |
| | } else { |
| | collide_cap = 0; |
| | } |
| | } |
| |
|
| | |
| | if (collide_side) { |
| | mju_addTo3(a_proj, pos2); |
| | return mjraw_SphereSphere(con, margin, pos1, mat1, size1, a_proj, mat2, size2); |
| | } |
| |
|
| | |
| | if (collide_cap) { |
| | const mjtNum flipmat[9] = { |
| | -mat2[0], mat2[1], -mat2[2], |
| | -mat2[3], mat2[4], -mat2[5], |
| | -mat2[6], mat2[7], -mat2[8] |
| | }; |
| | const mjtNum* mat_cap; |
| | mjtNum pos_cap[3]; |
| | if (x > 0) { |
| | mju_addScl3(pos_cap, pos2, axis, height); |
| | mat_cap = mat2; |
| | } else { |
| | mju_addScl3(pos_cap, pos2, axis, -height); |
| | mat_cap = flipmat; |
| | } |
| | int ncon = mjraw_PlaneSphere(con, margin, pos_cap, mat_cap, size2, pos1, mat1, size1); |
| | if (ncon) { |
| | |
| | mju_scl3(con->frame, con->frame, -1); |
| | } |
| | return ncon; |
| | } |
| |
|
| | |
| | mju_scl3(p_proj, p_proj, size2[0] / mju_sqrt(p_proj_sqr)); |
| | mju_scl3(vec, axis, x > 0 ? height : -height); |
| | mju_addTo3(vec, p_proj); |
| | mju_addTo3(vec, pos2); |
| |
|
| | |
| | mjtNum size_zero[1] = {0}; |
| | return mjraw_SphereSphere(con, margin, pos1, mat1, size1, vec, mat2, size_zero); |
| | } |
| |
|
| |
|
| |
|
| | |
| | int mjraw_CapsuleCapsule(mjContact* con, mjtNum margin, |
| | const mjtNum* pos1, const mjtNum* mat1, const mjtNum* size1, |
| | const mjtNum* pos2, const mjtNum* mat2, const mjtNum* size2) { |
| | |
| | mjtNum axis1[3] = {mat1[2] * size1[1], mat1[5] * size1[1], mat1[8] * size1[1]}; |
| | mjtNum axis2[3] = {mat2[2] * size2[1], mat2[5] * size2[1], mat2[8] * size2[1]}; |
| | mjtNum dif[3] = {pos1[0] - pos2[0], pos1[1] - pos2[1], pos1[2] - pos2[2]}; |
| |
|
| | |
| | mjtNum ma = mju_dot3(axis1, axis1); |
| | mjtNum mb = -mju_dot3(axis1, axis2); |
| | mjtNum mc = mju_dot3(axis2, axis2); |
| | mjtNum u = -mju_dot3(axis1, dif); |
| | mjtNum v = mju_dot3(axis2, dif); |
| | mjtNum det = ma*mc - mb*mb; |
| |
|
| | |
| | if (mju_abs(det) >= mjMINVAL) { |
| | |
| | mjtNum x1 = (mc*u - mb*v) / det; |
| | mjtNum x2 = (ma*v - mb*u) / det; |
| |
|
| | if (x1 > 1) { |
| | x1 = 1; |
| | x2 = (v - mb) / mc; |
| | } else if (x1 < -1) { |
| | x1 = -1; |
| | x2 = (v + mb) / mc; |
| | } |
| | if (x2 > 1) { |
| | x2 = 1; |
| | x1 = mju_clip((u - mb) / ma, -1, 1); |
| | } else if (x2 < -1) { |
| | x2 = -1; |
| | x1 = mju_clip((u + mb) / ma, -1, 1); |
| | } |
| |
|
| | |
| | mjtNum vec1[3], vec2[3]; |
| | mju_scl3(vec1, axis1, x1); |
| | mju_addTo3(vec1, pos1); |
| | mju_scl3(vec2, axis2, x2); |
| | mju_addTo3(vec2, pos2); |
| |
|
| | return mjraw_SphereSphere(con, margin, vec1, mat1, size1, vec2, mat2, size2); |
| | } |
| |
|
| | |
| | else { |
| | |
| | mjtNum vec1[3]; |
| | mju_add3(vec1, pos1, axis1); |
| | mjtNum x2 = mju_clip((v - mb) / mc, -1, 1); |
| |
|
| | mjtNum vec2[3]; |
| | mju_scl3(vec2, axis2, x2); |
| | mju_addTo3(vec2, pos2); |
| | int n1 = mjraw_SphereSphere(con, margin, vec1, mat1, size1, vec2, mat2, size2); |
| |
|
| | |
| | mju_sub3(vec1, pos1, axis1); |
| | x2 = mju_clip((v + mb) / mc, -1, 1); |
| | mju_scl3(vec2, axis2, x2); |
| | mju_addTo3(vec2, pos2); |
| | int n2 = mjraw_SphereSphere(con+n1, margin, vec1, mat1, size1, vec2, mat2, size2); |
| |
|
| | |
| | if (n1+n2 >= 2) { |
| | return n1+n2; |
| | } |
| |
|
| | |
| | mju_add3(vec2, pos2, axis2); |
| | mjtNum x1 = mju_clip((u - mb) / ma, -1, 1); |
| | mju_scl3(vec1, axis1, x1); |
| | mju_addTo3(vec1, pos1); |
| | int n3 = mjraw_SphereSphere(con+n1+n2, margin, vec1, mat1, size1, vec2, mat2, size2); |
| |
|
| | |
| | if (n1+n2+n3 >= 2) { |
| | return n1+n2+n3; |
| | } |
| |
|
| | |
| | mju_sub3(vec2, pos2, axis2); |
| | x1 = mju_clip((u + mb) / ma, -1, 1); |
| | mju_scl3(vec1, axis1, x1); |
| | mju_addTo3(vec1, pos1); |
| | int n4 = mjraw_SphereSphere(con+n1+n2+n3, margin, vec1, mat1, size1, vec2, mat2, size2); |
| |
|
| | return n1+n2+n3+n4; |
| | } |
| | } |
| |
|
| |
|
| |
|
| | |
| | int mjc_CapsuleCapsule(const mjModel* m, const mjData* d, |
| | mjContact* con, int g1, int g2, mjtNum margin) { |
| | mjGETINFO |
| | return mjraw_CapsuleCapsule(con, margin, pos1, mat1, size1, pos2, mat2, size2); |
| | } |
| |
|
| |
|
| |
|
| | |
| | static mjtNum areaSign(const mjtNum p1[2], const mjtNum p2[2], const mjtNum p3[2]) { |
| | return mju_sign((p1[0]-p3[0])*(p2[1]-p3[1]) - (p2[0]-p3[0])*(p1[1]-p3[1])); |
| | } |
| |
|
| |
|
| |
|
| | |
| | static mjtNum pointSegment(mjtNum res[2], const mjtNum p[2], |
| | const mjtNum u[2], const mjtNum v[2]) { |
| | |
| | mjtNum uv[2] = {v[0]-u[0], v[1]-u[1]}; |
| | mjtNum up[2] = {p[0]-u[0], p[1]-u[1]}; |
| |
|
| | |
| | mjtNum a = mju_dot(uv, up, 2) / mju_max(mjMINVAL, mju_dot(uv, uv, 2)); |
| |
|
| | |
| | if (a <= 0) { |
| | res[0] = u[0]; |
| | res[1] = u[1]; |
| | } else if (a >= 1) { |
| | res[0] = v[0]; |
| | res[1] = v[1]; |
| | } else { |
| | mju_addScl(res, u, uv, a, 2); |
| | } |
| |
|
| | |
| | return mju_sqrt((res[0]-p[0])*(res[0]-p[0]) + (res[1]-p[1])*(res[1]-p[1])); |
| | } |
| |
|
| |
|
| |
|
| | |
| | int mjraw_SphereTriangle(mjContact* con, mjtNum margin, |
| | const mjtNum* s, mjtNum rs, |
| | const mjtNum* t1, const mjtNum* t2, const mjtNum* t3, mjtNum rt) { |
| | mjtNum rbound = margin + rs + rt; |
| | mjtNum X[3]; |
| |
|
| | |
| | mjtNum S[3] = { s[0]-t1[0], s[1]-t1[1], s[2]-t1[2]}; |
| | mjtNum A[3] = {t2[0]-t1[0], t2[1]-t1[1], t2[2]-t1[2]}; |
| | mjtNum B[3] = {t3[0]-t1[0], t3[1]-t1[1], t3[2]-t1[2]}; |
| |
|
| | |
| | mjtNum N[3]; |
| | mju_cross(N, A, B); |
| | mju_normalize3(N); |
| |
|
| | |
| | mjtNum dstS = mju_dot3(N, S); |
| | if (mju_abs(dstS) > rbound) { |
| | return 0; |
| | } |
| |
|
| | |
| | mjtNum P[3]; |
| | mju_addScl3(P, S, N, -dstS); |
| |
|
| | |
| | mjtNum V1[3], V2[3]; |
| | mju_copy3(V1, A); |
| | mjtNum lenA = mju_normalize3(V1); |
| | mju_cross(V2, N, A); |
| | mju_normalize3(V2); |
| |
|
| | |
| | mjtNum o[2] = {0, 0}; |
| | mjtNum a[2] = {lenA, 0}; |
| | mjtNum b[2] = {mju_dot3(V1, B), mju_dot3(V2, B)}; |
| | mjtNum p[2] = {mju_dot3(V1, P), mju_dot3(V2, P)}; |
| |
|
| | |
| | mjtNum sign1 = areaSign(p, o, a); |
| | mjtNum sign2 = areaSign(p, a, b); |
| | mjtNum sign3 = areaSign(p, b, o); |
| |
|
| | |
| | if (sign1 == sign2 && sign2 == sign3) { |
| | |
| | mju_copy3(X, P); |
| | } |
| |
|
| | |
| | else { |
| | |
| | mjtNum x[3][2], dstx[3]; |
| | dstx[0] = pointSegment(x[0], p, o, a); |
| | dstx[1] = pointSegment(x[1], p, a, b); |
| | dstx[2] = pointSegment(x[2], p, b, o); |
| |
|
| | |
| | int best = (dstx[0] < dstx[1] && dstx[0] < dstx[2]) ? 0 : (dstx[1] < dstx[2] ? 1 : 2); |
| |
|
| | |
| | mju_scl3(X, V1, x[best][0]); |
| | mju_addToScl3(X, V2, x[best][1]); |
| | } |
| |
|
| | |
| | |
| | mjtNum nrm[3] = {X[0]-S[0], X[1]-S[1], X[2]-S[2]}; |
| | mjtNum dst = mju_normalize3(nrm); |
| |
|
| | |
| | if (dst > rbound) { |
| | return 0; |
| | } |
| |
|
| | |
| | con[0].dist = dst - rs - rt; |
| | mju_addScl3(con[0].pos, s, nrm, rs + con[0].dist/2); |
| | mju_copy3(con[0].frame, nrm); |
| | mju_zero3(con[0].frame+3); |
| |
|
| | return 1; |
| | } |
| |
|