Skip to content

Commit fc8979e

Browse files
haroonqcopybara-github
authored andcommitted
Add test for checking exhausted geoms.
PiperOrigin-RevId: 812776271 Change-Id: Ic9456ab201610a69237182ac22147e3d3e240308
1 parent c31f118 commit fc8979e

File tree

1 file changed

+67
-38
lines changed

1 file changed

+67
-38
lines changed

test/engine/engine_vis_visualize_test.cc

Lines changed: 67 additions & 38 deletions
Original file line numberDiff line numberDiff line change
@@ -12,7 +12,6 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#include <cstring>
1615
#include <string>
1716

1817
#include <gmock/gmock.h>
@@ -25,56 +24,86 @@ namespace mujoco {
2524
namespace {
2625

2726
using ::testing::NotNull;
28-
using MjvSceneTest = MujocoTest;
29-
30-
constexpr int kMaxGeom = 10000;
3127

3228
static const char* const kModelPath = "testdata/model.xml";
3329

34-
TEST_F(MjvSceneTest, UpdateScene) {
35-
for (const char* path : {kModelPath}) {
36-
const std::string xml_path = GetTestDataFilePath(path);
37-
mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, 0, 0);
38-
ASSERT_THAT(model, NotNull()) << "Failed to load model from " << path;
39-
mjData* data = mj_makeData(model);
40-
41-
while (data->time < .2) {
42-
mj_step(model, data);
30+
class MjvSceneTest : public MujocoTest {
31+
protected:
32+
static constexpr int kMaxGeom = 10000;
33+
34+
void InitSceneObjects(mjModel* model, int maxgeom = kMaxGeom) {
35+
mjv_defaultScene(&scn_);
36+
mjv_makeScene(model, &scn_, maxgeom);
37+
mjv_defaultOption(&opt_);
38+
mjv_defaultPerturb(&pert_);
39+
mjv_defaultFreeCamera(model, &cam_);
40+
41+
// enable flags to exercise additional code paths
42+
for (int i = 0; i < mjNVISFLAG; ++i) {
43+
opt_.flags[i] = 1;
4344
}
45+
}
4446

45-
mjvScene scn;
46-
mjv_defaultScene(&scn);
47-
mjv_makeScene(model, &scn, kMaxGeom);
47+
void FreeSceneObjects() {
48+
mjv_freeScene(&scn_);
49+
}
4850

49-
mjvOption opt;
50-
mjv_defaultOption(&opt);
51+
mjvScene scn_;
52+
mjvOption opt_;
53+
mjvPerturb pert_;
54+
mjvCamera cam_;
55+
};
5156

52-
mjvPerturb pert;
53-
mjv_defaultPerturb(&pert);
57+
TEST_F(MjvSceneTest, UpdateScene) {
58+
const std::string xml_path = GetTestDataFilePath(kModelPath);
59+
mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, 0, 0);
60+
ASSERT_THAT(model, NotNull()) << "Failed to load model from " << kModelPath;
5461

55-
mjvCamera cam;
56-
mjv_defaultFreeCamera(model, &cam);
62+
InitSceneObjects(model);
5763

58-
// Enable all flags to exercise all code paths
59-
for (int i = 0; i < mjNVISFLAG; ++i) {
60-
opt.flags[i] = 1;
61-
}
64+
mjData* data = mj_makeData(model);
65+
while (data->time < .2) {
66+
mj_step(model, data);
67+
}
6268

63-
mjv_updateScene(model, data, &opt, &pert, &cam, mjCAT_ALL, &scn);
64-
EXPECT_GT(scn.ngeom, 0);
65-
if (model->nskin) EXPECT_GT(scn.nskin, 0);
66-
EXPECT_GT(scn.nlight, 0);
69+
mjv_updateScene(model, data, &opt_, &pert_, &cam_, mjCAT_ALL, &scn_);
70+
EXPECT_GT(scn_.ngeom, 0);
71+
EXPECT_GT(scn_.nlight, 0);
72+
if (model->nskin) EXPECT_GT(scn_.nskin, 0);
73+
if (model->nflex) EXPECT_GT(scn_.nflex, 0);
6774

68-
mjv_updateScene(model, data, &opt, &pert, &cam, mjCAT_ALL, &scn);
75+
mjv_updateScene(model, data, &opt_, &pert_, &cam_, mjCAT_ALL, &scn_);
6976

70-
// call mj_copyData to expose any memory leaks mjv_updateScene.
71-
mjData* data_copy = mj_copyData(nullptr, model, data);
77+
// call mj_copyData to expose any memory leaks in mjv_updateScene
78+
mjData* data_copy = mj_copyData(nullptr, model, data);
7279

73-
mjv_freeScene(&scn);
74-
mj_deleteData(data_copy);
75-
mj_deleteData(data);
76-
mj_deleteModel(model);
77-
}
80+
mj_deleteData(data_copy);
81+
mj_deleteData(data);
82+
83+
FreeSceneObjects();
84+
mj_deleteModel(model);
85+
}
86+
87+
TEST_F(MjvSceneTest, UpdateSceneGeomsExhausted) {
88+
const std::string xml_path = GetTestDataFilePath(kModelPath);
89+
mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, 0, 0);
90+
ASSERT_THAT(model, NotNull()) << "Failed to load model from " << kModelPath;
91+
92+
const int maxgeoms = 1;
93+
InitSceneObjects(model, maxgeoms);
94+
95+
mjData* data = mj_makeData(model);
96+
mj_forward(model, data);
97+
98+
// clear handlers to avoid test failure; we are explicitly expecting a warning
99+
mju_clearHandlers();
100+
mjv_updateScene(model, data, &opt_, &pert_, &cam_, mjCAT_ALL, &scn_);
101+
EXPECT_EQ(scn_.ngeom, maxgeoms);
102+
EXPECT_EQ(data->warning[mjWARN_VGEOMFULL].number, 1);
103+
104+
mj_deleteData(data);
105+
FreeSceneObjects();
106+
mj_deleteModel(model);
78107
}
79108

80109
} // namespace

0 commit comments

Comments
 (0)