Skip to content

Commit

Permalink
Wrap LibCCD MPR function in a macro and initialize ccd_t struct.
Browse files Browse the repository at this point in the history
PiperOrigin-RevId: 634556417
Change-Id: I6a980e9b86c082523758fa401fbc75fcdc798c6b
  • Loading branch information
kbayes authored and Copybara-Service committed May 16, 2024
1 parent d58010c commit f6f9ff5
Showing 1 changed file with 11 additions and 3 deletions.
14 changes: 11 additions & 3 deletions src/engine/engine_collision_convex.c
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,8 @@
#include "engine/engine_util_misc.h"
#include "engine/engine_util_spatial.h"

// the LibCCD penetration function we use (ccdMPRPenetration or ccdGJKPenetration)
#define _mjCCDPENETRATION ccdMPRPenetration

// ccd center function
void mjccd_center(const void *obj, ccd_vec3_t *center) {
Expand Down Expand Up @@ -273,7 +275,7 @@ static int mjc_MPRIteration(mjtCCD* obj1, mjtCCD* obj2, const ccd_t* ccd,
mjContact* con, mjtNum margin) {
ccd_vec3_t dir, pos;
ccd_real_t depth;
if (ccdMPRPenetration(obj1, obj2, ccd, &depth, &dir, &pos) == 0) {
if (_mjCCDPENETRATION(obj1, obj2, ccd, &depth, &dir, &pos) == 0) {
// contact is found but normal is undefined
if (ccdVec3Eq(&dir, ccd_vec3_origin)) {
return 0;
Expand Down Expand Up @@ -343,6 +345,7 @@ int mjc_Convex(const mjModel* m, const mjData* d,
mjtCCD obj2 = {m, d, g2, -1, -1, -1, -1, margin, {1, 0, 0, 0}};

// init ccd structure
CCD_INIT(&ccd);
ccd.first_dir = ccdFirstDirDefault;
ccd.center1 = mjccd_center;
ccd.center2 = mjccd_center;
Expand Down Expand Up @@ -747,6 +750,7 @@ int mjc_ConvexHField(const mjModel* m, const mjData* d,
//------------------------------------- collision testing

// init ccd structure
CCD_INIT(&ccd);
ccd.first_dir = prism_firstdir;
ccd.center1 = prism_center;
ccd.center2 = mjccd_center;
Expand Down Expand Up @@ -787,7 +791,7 @@ int mjc_ConvexHField(const mjModel* m, const mjData* d,
}

// run MPR, save contact
if (ccdMPRPenetration(&prism, &obj, &ccd, &depth, &dirccd, &vecccd) == 0 &&
if (_mjCCDPENETRATION(&prism, &obj, &ccd, &depth, &dirccd, &vecccd) == 0 &&
!ccdVec3Eq(&dirccd, ccd_vec3_origin)) {
// fill in contact data, transform to global coordinates
con[cnt].dist = -depth;
Expand Down Expand Up @@ -1092,6 +1096,7 @@ int mjc_ConvexElem(const mjModel* m, const mjData* d, mjContact* con,
mjtCCD obj2 = {m, d, -1, -1, f2, e2, -1, margin, {1, 0, 0, 0}};

// init ccd structure
CCD_INIT(&ccd);
ccd.first_dir = ccdFirstDirDefault;
ccd.center1 = mjccd_center;
ccd.center2 = mjccd_center;
Expand Down Expand Up @@ -1197,6 +1202,7 @@ int mjc_HFieldElem(const mjModel* m, const mjData* d, mjContact* con,
//------------------------------------- collision testing

// init ccd structure
CCD_INIT(&ccd);
ccd.first_dir = prism_firstdir;
ccd.center1 = prism_center;
ccd.center2 = mjccd_center;
Expand Down Expand Up @@ -1234,7 +1240,7 @@ int mjc_HFieldElem(const mjModel* m, const mjData* d, mjContact* con,
}

// run MPR, save contact
if (ccdMPRPenetration(&prism, &obj, &ccd, &depth, &dirccd, &vecccd) == 0) {
if (_mjCCDPENETRATION(&prism, &obj, &ccd, &depth, &dirccd, &vecccd) == 0) {
if (!ccdVec3Eq(&dirccd, ccd_vec3_origin)) {
// fill in contact data, transform to global coordinates
con[cnt].dist = -depth;
Expand Down Expand Up @@ -1266,3 +1272,5 @@ int mjc_HFieldElem(const mjModel* m, const mjData* d, mjContact* con,

return cnt;
}

#undef _mjCCDPENETRATION

0 comments on commit f6f9ff5

Please sign in to comment.