Skip to content

Commit daba00c

Browse files
kbayescopybara-github
authored andcommitted
Fix a box-box bad collision in NativeCCD.
PiperOrigin-RevId: 713683497 Change-Id: I0c4cfd55d00faa196d8759046c87ee4ef74f01ab
1 parent 9004934 commit daba00c

File tree

2 files changed

+68
-4
lines changed

2 files changed

+68
-4
lines changed

src/engine/engine_collision_gjk.c

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -1104,19 +1104,19 @@ static int polytope4(Polytope* pt, mjCCDStatus* status, mjCCDObj* obj1, mjCCDObj
11041104
int v4 = newVertex(pt, status->simplex1 + 9, status->simplex2 + 9);
11051105

11061106
// if the origin is on a face, replace the 3-simplex with a 2-simplex
1107-
if (attachFace(pt, v1, v2, v3, 1, 3, 2) == 0.0) {
1107+
if (attachFace(pt, v1, v2, v3, 1, 3, 2) < mjMINVAL) {
11081108
replaceSimplex3(pt, status, v1, v2, v3);
11091109
return polytope3(pt, status, obj1, obj2);
11101110
}
1111-
if (attachFace(pt, v1, v4, v2, 2, 3, 0) == 0.0) {
1111+
if (attachFace(pt, v1, v4, v2, 2, 3, 0) < mjMINVAL) {
11121112
replaceSimplex3(pt, status, v1, v4, v2);
11131113
return polytope3(pt, status, obj1, obj2);
11141114
}
1115-
if (attachFace(pt, v1, v3, v4, 0, 3, 1) == 0.0) {
1115+
if (attachFace(pt, v1, v3, v4, 0, 3, 1) < mjMINVAL) {
11161116
replaceSimplex3(pt, status, v1, v3, v4);
11171117
return polytope3(pt, status, obj1, obj2);
11181118
}
1119-
if (attachFace(pt, v4, v3, v2, 2, 0, 1) == 0.0) {
1119+
if (attachFace(pt, v4, v3, v2, 2, 0, 1) < mjMINVAL) {
11201120
replaceSimplex3(pt, status, v4, v3, v2);
11211121
return polytope3(pt, status, obj1, obj2);
11221122
}

test/engine/engine_collision_gjk_test.cc

Lines changed: 64 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -335,6 +335,70 @@ TEST_F(MjGjkTest, BoxBoxDepth2) {
335335
mj_deleteModel(model);
336336
}
337337

338+
TEST_F(MjGjkTest, BoxBoxDepth3) {
339+
static constexpr char xml[] = R"(
340+
<mujoco>
341+
<worldbody>
342+
<geom name="geom1" type="box" pos="0 0 0" size="0.25 0.25 0.05"/>
343+
<geom name="geom2" type="box" pos="0 0 0" size="0.25 0.25 0.05"/>
344+
</worldbody>
345+
</mujoco>)";
346+
347+
std::array<char, 1000> error;
348+
mjModel* model = LoadModelFromString(xml, error.data(), error.size());
349+
ASSERT_THAT(model, NotNull()) << "Failed to load model: " << error.data();
350+
351+
mjData* data = mj_makeData(model);
352+
mj_forward(model, data);
353+
354+
mjtNum* xmat = data->geom_xmat;
355+
mjtNum* xpos = data->geom_xpos;
356+
357+
xmat[0] = 0.965925826289068201191412299522;
358+
xmat[1] = -0.258819045102520739476403832668;
359+
xmat[2] = 0.000000000000000006339100926609;
360+
xmat[3] = 0.258819045102520739476403832668;
361+
xmat[4] = 0.965925826289068201191412299522;
362+
xmat[5] = -0.000000000000000214827792362716;
363+
xmat[6] = 0.000000000000000049478422780336;
364+
xmat[7] = 0.000000000000000209148392896446;
365+
xmat[8] = 1.000000000000000000000000000000;
366+
367+
xpos[0] = -0.015346499999999199323474918799;
368+
xpos[1] = -0.023505500000000002086553152481;
369+
xpos[2] = -4.562296442400120888294168253196;
370+
371+
xmat = data->geom_xmat + 9;
372+
xpos = data->geom_xpos + 3;
373+
374+
xmat[0] = 0.866025403784438707610604524234;
375+
xmat[1] = -0.499999999999999944488848768742;
376+
xmat[2] = 0.000000000000000018716705841316;
377+
xmat[3] = 0.499999999999999944488848768742;
378+
xmat[4] = 0.866025403784438707610604524234;
379+
xmat[5] = -0.000000000000000263161736875730;
380+
xmat[6] = 0.000000000000000115371725704125;
381+
xmat[7] = 0.000000000000000237263102359077;
382+
xmat[8] = 1.000000000000000000000000000000;
383+
384+
xpos[0] = -0.015346499999999797803074130798;
385+
xpos[1] = -0.023505499999999998617106200527;
386+
xpos[2] = -4.659230360891631228525966434972;
387+
388+
int geom1 = mj_name2id(model, mjOBJ_GEOM, "geom1");
389+
int geom2 = mj_name2id(model, mjOBJ_GEOM, "geom2");
390+
mjtNum dir[3], pos[3];
391+
mjtNum dist = Penetration(model, data, geom1, geom2, dir, pos);
392+
393+
EXPECT_NEAR(dist, -0.003066, kTolerance);
394+
EXPECT_NEAR(dir[0], 0, kTolerance);
395+
EXPECT_NEAR(dir[1], 0, kTolerance);
396+
EXPECT_NEAR(dir[2], -1, kTolerance);
397+
398+
mj_deleteData(data);
399+
mj_deleteModel(model);
400+
}
401+
338402
TEST_F(MjGjkTest, BoxBoxTouching) {
339403
static constexpr char xml[] = R"(
340404
<mujoco>

0 commit comments

Comments
 (0)