| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| |
|
| | |
| |
|
| | #include <cstdio> |
| | #include <gmock/gmock.h> |
| | #include <gtest/gtest.h> |
| | #include <mujoco/mjdata.h> |
| | #include <mujoco/mjmodel.h> |
| | #include <mujoco/mjtnum.h> |
| | #include <mujoco/mujoco.h> |
| | #include "src/engine/engine_collision_sdf.h" |
| | #include "test/fixture.h" |
| |
|
| | namespace mujoco { |
| | namespace { |
| |
|
| | using ::testing::NotNull; |
| | using SdfTest = MujocoTest; |
| |
|
| | static constexpr int kpoints = 6; |
| | static constexpr int kgeoms = 5; |
| | static constexpr char kSdfModel[] = R"( |
| | <mujoco> |
| | <worldbody> |
| | <geom type="plane" size="5 5 .1" pos="0 0 -1"/> |
| | <body pos="-.1 .2 2" euler="0 0 45"> |
| | <geom type="sphere" size="1"/> |
| | <geom type="capsule" size=".1" fromto="-2 -2 1 2 2 1"/> |
| | <geom type="cylinder" size="1" fromto="0 0 0 2 0 0"/> |
| | <geom type="box" size="1 1 1"/> |
| | </body> |
| | </worldbody> |
| | </mujoco> |
| | )"; |
| |
|
| | TEST_F(SdfTest, SdfPrimitive) { |
| | mjModel* model = LoadModelFromString(kSdfModel); |
| | ASSERT_THAT(model, NotNull()); |
| | mjData* data = mj_makeData(model); |
| | ASSERT_THAT(data, NotNull()); |
| | ASSERT_THAT(model->ngeom, kgeoms); |
| |
|
| | mjSDF sdf; |
| | const mjpPlugin* null_plugin = NULL; |
| | mjtNum gradient[3], dist[kgeoms][kpoints] = { |
| | {0, 0, 0, 0, 1, 1}, |
| | {-1, 0, 0, mju_sqrt(2)-1, mju_sqrt(2)-1, mju_sqrt(3)-1}, |
| | {-.1, .9, .9, mju_sqrt(2)-.1, .9, mju_sqrt(2)-.1}, |
| | {-1, 0, 0, mju_sqrt(2)-1, 0, mju_sqrt(2)-1}, |
| | {-mju_sqrt(3), 0, 0, 0, 0, 0}, |
| | }; |
| | mjtNum points[kpoints][3] = {{0, 0, 0}, {1, 0, 0}, {0, 1, 0}, |
| | {1, 1, 0}, {0, 1, 1}, {1, 1, 1}}; |
| |
|
| | for (int i = 0; i < kgeoms; i++) { |
| | sdf.plugin = &null_plugin; |
| | sdf.id = &i; |
| | sdf.type = mjSDFTYPE_SINGLE; |
| | sdf.geomtype = (mjtGeom*)(model->geom_type+i); |
| | for (int j = 0; j < kpoints; j++) { |
| | EXPECT_NEAR(mjc_distance(model, data, &sdf, points[j]), dist[i][j], 1e-9); |
| | mjc_gradient(model, data, &sdf, gradient, points[j]); |
| | } |
| | } |
| |
|
| | mj_deleteData(data); |
| | mj_deleteModel(model); |
| | } |
| |
|
| | } |
| | } |
| |
|