| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| |
|
| | #include <cstring> |
| | #include <string> |
| |
|
| | #include <gmock/gmock.h> |
| | #include <gtest/gtest.h> |
| | #include <mujoco/mjvisualize.h> |
| | #include <mujoco/mujoco.h> |
| | #include "test/fixture.h" |
| |
|
| | namespace mujoco { |
| | namespace { |
| |
|
| | using ::testing::NotNull; |
| | using MjvSceneTest = MujocoTest; |
| |
|
| | constexpr int kMaxGeom = 10000; |
| |
|
| | static const char* const kModelPath = "testdata/model.xml"; |
| |
|
| | TEST_F(MjvSceneTest, UpdateScene) { |
| | for (const char* path : {kModelPath}) { |
| | const std::string xml_path = GetTestDataFilePath(path); |
| | mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, 0, 0); |
| | ASSERT_THAT(model, NotNull()) << "Failed to load model from " << path; |
| | mjData* data = mj_makeData(model); |
| |
|
| | while (data->time < .2) { |
| | mj_step(model, data); |
| | } |
| |
|
| | mjvScene scn; |
| | mjv_defaultScene(&scn); |
| | mjv_makeScene(model, &scn, kMaxGeom); |
| |
|
| | mjvOption opt; |
| | mjv_defaultOption(&opt); |
| |
|
| | mjvPerturb pert; |
| | mjv_defaultPerturb(&pert); |
| |
|
| | mjvCamera cam; |
| | mjv_defaultFreeCamera(model, &cam); |
| |
|
| | |
| | for (int i = 0; i < mjNVISFLAG; ++i) { |
| | opt.flags[i] = 1; |
| | } |
| |
|
| | mjv_updateScene(model, data, &opt, &pert, &cam, mjCAT_ALL, &scn); |
| | EXPECT_GT(scn.ngeom, 0); |
| | if (model->nskin) EXPECT_GT(scn.nskin, 0); |
| | EXPECT_GT(scn.nlight, 0); |
| |
|
| | mjv_updateScene(model, data, &opt, &pert, &cam, mjCAT_ALL, &scn); |
| |
|
| | |
| | mjData* data_copy = mj_copyData(nullptr, model, data); |
| |
|
| | mjv_freeScene(&scn); |
| | mj_deleteData(data_copy); |
| | mj_deleteData(data); |
| | mj_deleteModel(model); |
| | } |
| | } |
| |
|
| | } |
| | } |
| |
|