File: engine_ray_test.cc

package info (click to toggle)
mujoco 2.2.2-3.2
  • links: PTS, VCS
  • area: main
  • in suites: forky, sid
  • size: 39,796 kB
  • sloc: ansic: 28,947; cpp: 28,897; cs: 14,241; python: 10,465; xml: 5,104; sh: 93; makefile: 34
file content (137 lines) | stat: -rw-r--r-- 4,131 bytes parent folder | download | duplicates (2)
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
// Copyright 2022 DeepMind Technologies Limited
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
//     http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

// Tests for ray casting.

#include <array>
#include <cstddef>
#include <cstring>
#include <string>

#include <gmock/gmock.h>
#include <gtest/gtest.h>
#include <mujoco/mjdata.h>
#include <mujoco/mjmodel.h>
#include <mujoco/mujoco.h>
#include "test/fixture.h"

namespace mujoco {
namespace {

static constexpr char kRayCastingModel[] = R"(
<mujoco>
  <worldbody>
    <geom name="static_group1" type="sphere" size=".1" pos="1 0 0"
     group="1"/>
    <body pos="0 0 0">
      <body pos="0 0 0">
        <geom name="group0" type="sphere" size=".1" pos="3 0 0"/>
      </body>
      <geom name="group2" type="sphere" size=".1" pos="5 0 0" group="2"/>
    </body>
  </worldbody>
</mujoco>
)";

using ::testing::NotNull;
using RayTest = MujocoTest;

TEST_F(RayTest, NoExclusions) {
  mjModel* model = LoadModelFromString(kRayCastingModel);
  ASSERT_THAT(model, NotNull());
  mjData* data = mj_makeData(model);
  ASSERT_THAT(data, NotNull());

  mjtNum pnt[] = {0.0, 0.0, 0.0};
  mjtNum vec[] = {1.0, 0.0, 0.0};
  mjtByte* geomgroup = nullptr;
  mjtByte flg_static = 1;  // Include static geoms
  int bodyexclude = -1;
  int geomid = -1;

  mj_kinematics(model, data);
  mjtNum distance = mj_ray(model, data, pnt, vec, geomgroup, flg_static,
                           bodyexclude, &geomid);
  EXPECT_STREQ(mj_id2name(model, mjOBJ_GEOM, geomid), "static_group1");
  EXPECT_FLOAT_EQ(distance, 0.9);
  mj_deleteData(data);
  mj_deleteModel(model);
}

TEST_F(RayTest, Exclusions) {
  mjModel* model = LoadModelFromString(kRayCastingModel);
  ASSERT_THAT(model, NotNull());
  mjData* data = mj_makeData(model);
  ASSERT_THAT(data, NotNull());

  mjtNum pnt[] = {0.0, 0.0, 0.0};
  mjtNum vec[] = {1.0, 0.0, 0.0};
  mjtByte geomgroup[] = {1, 1, 1};
  mjtByte flg_static = 1;
  int bodyexclude = -1;
  int geomid = -1;

  mj_kinematics(model, data);
  mjtNum distance = mj_ray(model, data, pnt, vec, geomgroup, flg_static,
                           bodyexclude, &geomid);
  EXPECT_STREQ(mj_id2name(model, mjOBJ_GEOM, geomid), "static_group1");
  EXPECT_FLOAT_EQ(distance, 0.9);

  // Exclude nearest geom
  geomgroup[1] = 0;
  distance = mj_ray(model, data, pnt, vec, geomgroup, flg_static, bodyexclude,
                    &geomid);
  EXPECT_STREQ(mj_id2name(model, mjOBJ_GEOM, geomid), "group0");
  EXPECT_FLOAT_EQ(distance, 2.9);

  geomgroup[0] = 0;
  distance = mj_ray(model, data, pnt, vec, geomgroup, flg_static, bodyexclude,
                    &geomid);
  EXPECT_STREQ(mj_id2name(model, mjOBJ_GEOM, geomid), "group2");
  EXPECT_FLOAT_EQ(distance, 4.9);

  geomgroup[2] = 0;
  distance = mj_ray(model, data, pnt, vec, geomgroup, flg_static, bodyexclude,
                    &geomid);
  EXPECT_EQ(geomid, -1);
  EXPECT_FLOAT_EQ(distance, -1);

  mj_deleteData(data);
  mj_deleteModel(model);
}

TEST_F(RayTest, ExcludeStatic) {
  mjModel* model = LoadModelFromString(kRayCastingModel);
  ASSERT_THAT(model, NotNull());
  mjData* data = mj_makeData(model);
  ASSERT_THAT(data, NotNull());

  mjtNum pnt[] = {0.0, 0.0, 0.0};
  mjtNum vec[] = {1.0, 0.0, 0.0};
  mjtByte geomgroup[] = {1, 1, 1};
  mjtByte flg_static = 0;  // Exclude static geoms
  int bodyexclude = -1;
  int geomid = -1;

  mj_kinematics(model, data);
  mjtNum distance = mj_ray(model, data, pnt, vec, geomgroup, flg_static,
                           bodyexclude, &geomid);
  EXPECT_STREQ(mj_id2name(model, mjOBJ_GEOM, geomid), "group0");
  EXPECT_FLOAT_EQ(distance, 2.9);
  mj_deleteData(data);
  mj_deleteModel(model);
}

}  // namespace
}  // namespace mujoco