// Copyright 2021 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 xml/xml_native_reader.cc. #include #include #include #include #include #include #include #include #include #include #include #include "src/cc/array_safety.h" #include "src/engine/engine_util_errmem.h" #include "src/xml/xml_api.h" #include "test/fixture.h" namespace mujoco { namespace { using ::std::string; using ::testing::AllOf; using ::testing::ElementsAre; using ::testing::Eq; using ::testing::FloatEq; using ::testing::HasSubstr; using ::testing::IsNan; using ::testing::IsNull; using ::testing::NotNull; using XMLReaderTest = MujocoTest; TEST_F(XMLReaderTest, UniqueElementTest) { std::array error; static constexpr char xml[] = R"( )"; mjModel* model = LoadModelFromString(xml, error.data(), error.size()); ASSERT_THAT(model, IsNull()); EXPECT_THAT(error.data(), HasSubstr("unique element 'flag' found 2 times")); } TEST_F(XMLReaderTest, MemorySize) { std::array error; { static constexpr char xml[] = R"( )"; mjModel* model = LoadModelFromString(xml, error.data(), error.size()); ASSERT_THAT(model, NotNull()) << error.data(); EXPECT_EQ(model->narena, 512); mj_deleteModel(model); } { static constexpr char xml[] = R"( )"; mjModel* model = LoadModelFromString(xml, error.data(), error.size()); ASSERT_THAT(model, NotNull()) << error.data(); EXPECT_EQ(model->narena, 1024); mj_deleteModel(model); } { static constexpr char xml[] = R"( )"; mjModel* model = LoadModelFromString(xml, error.data(), error.size()); ASSERT_THAT(model, NotNull()) << error.data(); EXPECT_EQ(model->narena, 10240); mj_deleteModel(model); } { static constexpr char xml[] = R"( )"; mjModel* model = LoadModelFromString(xml, error.data(), error.size()); ASSERT_THAT(model, NotNull()) << error.data(); EXPECT_EQ(model->narena, 4*1024*1024); mj_deleteModel(model); } { static constexpr char xml[] = R"( )"; mjModel* model = LoadModelFromString(xml, error.data(), error.size()); ASSERT_THAT(model, NotNull()) << error.data(); EXPECT_EQ(model->narena, 1024*1024*1024); mj_deleteModel(model); } { static constexpr char xml[] = R"( )"; mjModel* model = LoadModelFromString(xml, error.data(), error.size()); ASSERT_THAT(model, NotNull()) << error.data(); EXPECT_EQ(model->narena, 1024*1024*1024); mj_deleteModel(model); } } TEST_F(XMLReaderTest, InvalidMemorySize) { std::array error; { static constexpr char xml[] = R"( )"; mjModel* model = LoadModelFromString(xml, error.data(), error.size()); ASSERT_THAT(model, IsNull()); } { static constexpr char xml[] = R"( )"; mjModel* model = LoadModelFromString(xml, error.data(), error.size()); ASSERT_THAT(model, IsNull()); } { static constexpr char xml[] = R"( )"; mjModel* model = LoadModelFromString(xml, error.data(), error.size()); ASSERT_THAT(model, IsNull()); } { static constexpr char xml[] = R"( )"; mjModel* model = LoadModelFromString(xml, error.data(), error.size()); ASSERT_THAT(model, IsNull()); } } TEST_F(XMLReaderTest, InvalidNUserBody) { static constexpr char xml[] = R"( )"; std::array error; mjModel* model = LoadModelFromString(xml, error.data(), error.size()); ASSERT_THAT(model, IsNull()); EXPECT_THAT(error.data(), HasSubstr("nuser_body")); EXPECT_THAT(error.data(), HasSubstr("line 3")); } TEST_F(XMLReaderTest, InvalidNUserJoint) { static constexpr char xml[] = R"( )"; std::array error; mjModel* model = LoadModelFromString(xml, error.data(), error.size()); ASSERT_THAT(model, IsNull()); EXPECT_THAT(error.data(), HasSubstr("nuser_jnt")); EXPECT_THAT(error.data(), HasSubstr("line 3")); } TEST_F(XMLReaderTest, InvalidNUserGeom) { static constexpr char xml[] = R"( )"; std::array error; mjModel* model = LoadModelFromString(xml, error.data(), error.size()); ASSERT_THAT(model, IsNull()); EXPECT_THAT(error.data(), HasSubstr("nuser_geom")); EXPECT_THAT(error.data(), HasSubstr("line 3")); } TEST_F(XMLReaderTest, InvalidNUserSite) { static constexpr char xml[] = R"( )"; std::array error; mjModel* model = LoadModelFromString(xml, error.data(), error.size()); ASSERT_THAT(model, IsNull()); EXPECT_THAT(error.data(), HasSubstr("nuser_site")); EXPECT_THAT(error.data(), HasSubstr("line 3")); } TEST_F(XMLReaderTest, InvalidNUserCamera) { static constexpr char xml[] = R"( )"; std::array error; mjModel* model = LoadModelFromString(xml, error.data(), error.size()); ASSERT_THAT(model, IsNull()); EXPECT_THAT(error.data(), HasSubstr("nuser_cam")); EXPECT_THAT(error.data(), HasSubstr("line 3")); } TEST_F(XMLReaderTest, InvalidNUserTendon) { static constexpr char xml[] = R"( )"; std::array error; mjModel* model = LoadModelFromString(xml, error.data(), error.size()); ASSERT_THAT(model, IsNull()); EXPECT_THAT(error.data(), HasSubstr("nuser_tendon")); EXPECT_THAT(error.data(), HasSubstr("line 3")); } TEST_F(XMLReaderTest, InvalidNUserActuator) { static constexpr char xml[] = R"( )"; std::array error; mjModel* model = LoadModelFromString(xml, error.data(), error.size()); ASSERT_THAT(model, IsNull()); EXPECT_THAT(error.data(), HasSubstr("nuser_actuator")); EXPECT_THAT(error.data(), HasSubstr("line 3")); } TEST_F(XMLReaderTest, InvalidNUserSensor) { static constexpr char xml[] = R"( )"; std::array error; mjModel* model = LoadModelFromString(xml, error.data(), error.size()); ASSERT_THAT(model, IsNull()); EXPECT_THAT(error.data(), HasSubstr("nuser_sensor")); EXPECT_THAT(error.data(), HasSubstr("line 3")); } TEST_F(XMLReaderTest, CanParseInf) { static constexpr char xml[] = R"( )"; const double inf = std::numeric_limits::infinity(); mjModel* model = LoadModelFromString(xml); ASSERT_THAT(model, NotNull()); EXPECT_EQ(model->geom_pos[0], 0.5); EXPECT_EQ(model->geom_pos[1], -inf); EXPECT_THAT(model->geom_pos[2], inf); EXPECT_EQ(model->geom_pos[3], inf); EXPECT_EQ(model->geom_pos[4], -inf); EXPECT_EQ(model->geom_pos[5], inf); mj_deleteModel(model); } TEST_F(XMLReaderTest, CanParseNanAndRaisesWarning) { static constexpr char xml[] = R"( )"; std::array error; static char warning[1024]; warning[0] = '\0'; mju_user_warning = [](const char* msg) { util::strcpy_arr(warning, msg); }; mjModel* model = LoadModelFromString(xml, error.data(), error.size()); ASSERT_THAT(model, NotNull()); EXPECT_THAT(warning, HasSubstr("XML contains a 'NaN'")); EXPECT_THAT(model->geom_pos[0], IsNan()); EXPECT_THAT(model->geom_pos[1], IsNan()); EXPECT_THAT(model->geom_pos[2], IsNan()); EXPECT_EQ(model->geom_pos[3], 1); EXPECT_EQ(model->geom_pos[4], 0); EXPECT_THAT(model->geom_pos[5], IsNan()); mj_deleteModel(model); } TEST_F(XMLReaderTest, InvalidArrayElement) { static constexpr char xml[] = R"( )"; std::array error; mjModel* model = LoadModelFromString(xml, error.data(), error.size()); ASSERT_THAT(model, IsNull()); EXPECT_THAT(error.data(), HasSubstr("bad format in attribute 'axisangle'")); EXPECT_THAT(error.data(), HasSubstr("line 5")); } TEST_F(XMLReaderTest, InvalidArrayLength) { static constexpr char xml[] = R"( )"; std::array error; mjModel* model = LoadModelFromString(xml, error.data(), error.size()); ASSERT_THAT(model, IsNull()); EXPECT_THAT(error.data(), HasSubstr("has too much data")); EXPECT_THAT(error.data(), HasSubstr("line 5")); } TEST_F(XMLReaderTest, InvalidQuaternion) { static constexpr char xml[] = R"( )"; std::array error; mjModel* model = LoadModelFromString(xml, error.data(), error.size()); ASSERT_THAT(model, IsNull()); EXPECT_THAT(error.data(), HasSubstr("zero quaternion is not allowed")); EXPECT_THAT(error.data(), HasSubstr("line 5")); } TEST_F(XMLReaderTest, InvalidNumber) { static constexpr char xml[] = R"( )"; std::array error; mjModel* model = LoadModelFromString(xml, error.data(), error.size()); ASSERT_THAT(model, IsNull()); EXPECT_THAT(error.data(), HasSubstr("bad format in attribute 'axisangle'")); EXPECT_THAT(error.data(), HasSubstr("line 5")); } TEST_F(XMLReaderTest, InvalidNumberRange) { static constexpr char xml[] = R"( )"; std::array error; mjModel* model = LoadModelFromString(xml, error.data(), error.size()); ASSERT_THAT(model, IsNull()); EXPECT_THAT(error.data(), HasSubstr("number is too large in attribute 'face'")); EXPECT_THAT(error.data(), HasSubstr("line 4")); } TEST_F(XMLReaderTest, InvalidNumberOfAttributes) { static constexpr char xml[] = R"( )"; std::array error; mjModel* model = LoadModelFromString(xml, error.data(), error.size()); ASSERT_THAT(model, IsNull()); EXPECT_THAT(error.data(), HasSubstr("size 2 must be positive")); EXPECT_THAT(error.data(), HasSubstr("line 6")); } TEST_F(XMLReaderTest, AllowsSpaces) { static constexpr char xml[] = R"( )"; std::array error; mjModel* model = LoadModelFromString(xml, error.data(), error.size()); ASSERT_THAT(model, NotNull()); mj_deleteModel(model); } TEST_F(XMLReaderTest, InvalidDoubleOrientation) { std::string prefix = "<"; std::string suffix = "/>"; std::vector orientations = { R"( quat="0 1 0 0" )", R"( euler="1.7 2.9 0.1" )", R"( zaxis="1.7 2.9 0.1" )", R"( axisangle="1.7 2.9 0.1 0" )", R"( xyaxes="1.7 2.9 0.1 0.4 1.4 0.6" )", }; std::vector fields = { "geom", "body", "camera", "site" }; for (auto const& field : fields) { for (auto const& orient1 : orientations) { for (auto const& orient2 : orientations) { if (orient1 == orient2) continue; std::string xml = prefix + field + orient1 + orient2 + suffix; std::array error; mjModel* model = LoadModelFromString(xml.c_str(), error.data(), error.size()); ASSERT_THAT(model, IsNull()); EXPECT_THAT( error.data(), HasSubstr("multiple orientation specifiers are not allowed")); } } } } TEST_F(XMLReaderTest, ClassOverridesChildclass) { static constexpr char xml[] = R"( )"; std::array error; mjModel* model = LoadModelFromString(xml, error.data(), error.size()); ASSERT_THAT(model, NotNull()) << error.data(); EXPECT_EQ(model->geom_size[3*0], 2); EXPECT_EQ(model->geom_size[3*1], 3); EXPECT_EQ(model->geom_size[3*2], 2); EXPECT_EQ(model->geom_size[3*3], 3); mj_deleteModel(model); } TEST_F(XMLReaderTest, RepeatedDefaultName) { static constexpr char xml[] = R"( )"; std::array error; mjModel* model = LoadModelFromString(xml, error.data(), error.size()); ASSERT_THAT(model, IsNull()) << error.data(); EXPECT_THAT(error.data(), HasSubstr("repeated default class name")); } TEST_F(XMLReaderTest, InvalidDefaultClassName) { static constexpr char xml[] = R"( )"; std::array error; mjModel* model = LoadModelFromString(xml, error.data(), error.size()); ASSERT_THAT(model, IsNull()) << error.data(); EXPECT_THAT(error.data(), AllOf(HasSubstr("unknown default class name 'invalid'"), HasSubstr("Element 'geom'"), HasSubstr("line 10"))); } TEST_F(XMLReaderTest, InvalidTopDefaultClassName) { static constexpr char xml[] = R"( )"; std::array error; mjModel* model = LoadModelFromString(xml, error.data(), error.size()); ASSERT_THAT(model, IsNull()) << error.data(); EXPECT_THAT(error.data(), HasSubstr("top-level default class 'main' cannot be renamed")); } TEST_F(XMLReaderTest, ValidTopDefaultClassName) { static constexpr char xml[] = R"( )"; std::array error; mjModel* model = LoadModelFromString(xml, error.data(), error.size()); ASSERT_THAT(model, NotNull()) << error.data(); mj_deleteModel(model); } // ------------------------ test including ------------------------------------- // tiny RGB 2 x 3 PNG file static constexpr unsigned char kTinyPng[] = { 0x89, 0x50, 0x4e, 0x47, 0x0d, 0x0a, 0x1a, 0x0a, 0x00, 0x00, 0x00, 0x0d, 0x49, 0x48, 0x44, 0x52, 0x00, 0x00, 0x00, 0x03, 0x00, 0x00, 0x00, 0x02, 0x08, 0x02, 0x00, 0x00, 0x00, 0x12, 0x16, 0xf1, 0x4d, 0x00, 0x00, 0x00, 0x1c, 0x49, 0x44, 0x41, 0x54, 0x08, 0xd7, 0x63, 0x78, 0xc1, 0xc0, 0xc0, 0xc0, 0xf0, 0xbf, 0xb8, 0xb8, 0x98, 0x81, 0xe1, 0x3f, 0xc3, 0xff, 0xff, 0xff, 0xc5, 0xc4, 0xc4, 0x00, 0x46, 0xd7, 0x07, 0x7f, 0xd2, 0x52, 0xa1, 0x41, 0x00, 0x00, 0x00, 0x00, 0x49, 0x45, 0x4e, 0x44, 0xae, 0x42, 0x60, 0x82 }; // mesh OBJ file of a cube static constexpr char kTinyObj[] = R"( v -1 -1 1 v 1 -1 1 v -1 1 1 v 1 1 1 v -1 1 -1 v 1 1 -1 v -1 -1 -1 v 1 -1 -1)"; TEST_F(XMLReaderTest, IncludeTest) { static constexpr char xml[] = R"( )"; static constexpr char xml1[] = R"( )"; static constexpr char xml2[]= R"( )"; static constexpr char xml3[]= R"( )"; auto vfs = std::make_unique(); mj_defaultVFS(vfs.get()); mj_addBufferVFS(vfs.get(), "model1.xml", xml1, sizeof(xml1)); mj_addBufferVFS(vfs.get(), "model2.xml", xml2, sizeof(xml2)); mj_addBufferVFS(vfs.get(), "model3.xml", xml3, sizeof(xml3)); std::array error; mjModel* model = LoadModelFromString(xml, error.data(), error.size(), vfs.get()); ASSERT_THAT(model, NotNull()) << error.data(); EXPECT_EQ(mj_name2id(model, mjOBJ_GEOM, "ball"), 2); EXPECT_EQ(mj_name2id(model, mjOBJ_GEOM, "another_box"), 3); mj_deleteModel(model); mj_deleteVFS(vfs.get()); } TEST_F(XMLReaderTest, IncludeChildTest) { static constexpr char xml[] = R"( )"; std::array error; mjModel* model = LoadModelFromString(xml, error.data(), error.size()); ASSERT_THAT(model, IsNull()); EXPECT_THAT(error.data(), HasSubstr("Include element cannot have children")); mj_deleteModel(model); } TEST_F(XMLReaderTest, IncludeSameFileTest) { static constexpr char xml[] = R"( )"; static constexpr char xml1[] = R"( )"; auto vfs = std::make_unique(); mj_defaultVFS(vfs.get()); mj_addBufferVFS(vfs.get(), "model1.xml", xml1, sizeof(xml1)); std::array error; mjModel* model = LoadModelFromString(xml, error.data(), error.size(), vfs.get()); ASSERT_THAT(model, IsNull()); EXPECT_THAT(error.data(), HasSubstr("File 'model1.xml' already included")); mj_deleteModel(model); mj_deleteVFS(vfs.get()); } TEST_F(XMLReaderTest, IncludePathTest) { static constexpr char xml[] = R"( )"; static constexpr char xml1[] = R"( )"; static constexpr char xml2[]= R"( )"; static constexpr char xml3[]= R"( )"; mjVFS vfs; mj_defaultVFS(&vfs); mj_addBufferVFS(&vfs, "model.xml", xml, sizeof(xml)); mj_addBufferVFS(&vfs, "submodels/model1.xml", xml1, sizeof(xml1)); mj_addBufferVFS(&vfs, "submodels/model2.xml", xml2, sizeof(xml2)); mj_addBufferVFS(&vfs, "submodels/subsubmodels/model3.xml", xml3, sizeof(xml3)); std::array error; mjModel* model = mj_loadXML("model.xml", &vfs, error.data(), error.size()); ASSERT_THAT(model, NotNull()) << error.data(); EXPECT_EQ(mj_name2id(model, mjOBJ_GEOM, "ball"), 2); EXPECT_EQ(mj_name2id(model, mjOBJ_GEOM, "another_box"), 3); mj_deleteModel(model); mj_deleteVFS(&vfs); } TEST_F(XMLReaderTest, FallbackIncludePathTest) { static constexpr char xml[] = R"( )"; static constexpr char xml1[] = R"( )"; static constexpr char xml2[]= R"( )"; static constexpr char xml3[]= R"( )"; mjVFS vfs; mj_defaultVFS(&vfs); mj_addBufferVFS(&vfs, "model.xml", xml, sizeof(xml)); mj_addBufferVFS(&vfs, "model1.xml", xml1, sizeof(xml1)); mj_addBufferVFS(&vfs, "submodels/model2.xml", xml2, sizeof(xml2)); mj_addBufferVFS(&vfs, "subsubmodels/model3.xml", xml3, sizeof(xml3)); std::array error; mjModel* model = mj_loadXML("model.xml", &vfs, error.data(), error.size()); ASSERT_THAT(model, NotNull()) << error.data(); EXPECT_EQ(mj_name2id(model, mjOBJ_GEOM, "ball"), 2); EXPECT_EQ(mj_name2id(model, mjOBJ_GEOM, "another_box"), 3); mj_deleteModel(model); mj_deleteVFS(&vfs); } TEST_F(XMLReaderTest, MaterialTextureTest) { static constexpr char xml[] = R"( )"; mjVFS vfs; mj_defaultVFS(&vfs); mj_addBufferVFS(&vfs, "tiny0.png", kTinyPng, sizeof(kTinyPng)); mj_addBufferVFS(&vfs, "tiny1.png", kTinyPng, sizeof(kTinyPng)); mj_addBufferVFS(&vfs, "model.xml", xml, sizeof(xml)); char error[1024]; mjModel* model = mj_loadXML("model.xml", &vfs, error, 1024); EXPECT_THAT(model, NotNull()) << error; EXPECT_EQ(model->mat_texid[mjTEXROLE_RGB], 1); EXPECT_EQ(model->mat_texid[mjTEXROLE_METALLIC], 0); EXPECT_EQ(model->mat_texid[mjTEXROLE_ROUGHNESS], 0); EXPECT_EQ(model->mat_texid[mjTEXROLE_OCCLUSION], 0); mj_deleteModel(model); mj_deleteVFS(&vfs); } TEST_F(XMLReaderTest, LegacyMaterialTextureTest) { static constexpr char xml[] = R"( )"; mjVFS vfs; mj_defaultVFS(&vfs); mj_addBufferVFS(&vfs, "tiny0.png", kTinyPng, sizeof(kTinyPng)); mj_addBufferVFS(&vfs, "tiny1.png", kTinyPng, sizeof(kTinyPng)); mj_addBufferVFS(&vfs, "model.xml", xml, sizeof(xml)); char error[1024]; mjModel* model = mj_loadXML("model.xml", &vfs, error, 1024); EXPECT_THAT(model, NotNull()) << error; EXPECT_EQ(model->mat_texid[mjTEXROLE_RGB], 1); mj_deleteModel(model); mj_deleteVFS(&vfs); } TEST_F(XMLReaderTest, MaterialTextureFailTest) { static constexpr char xml[] = R"( )"; std::array error; mjModel* m = LoadModelFromString(xml, error.data(), error.size()); EXPECT_THAT(m, IsNull()); EXPECT_THAT(error.data(), HasSubstr("A material with a texture attribute " "cannot have layer sub-elements")); } TEST_F(XMLReaderTest, LargeTextureTest) { static constexpr char xml[] = R"( )"; std::array error; mjModel* model = LoadModelFromString(xml, error.data(), error.size()); EXPECT_THAT(model, IsNull()); mj_deleteModel(model); } TEST_F(XMLReaderTest, HugeTextureTest) { static constexpr char xml[] = R"( )"; std::array error; mjModel* model = LoadModelFromString(xml, error.data(), error.size()); EXPECT_THAT(model, IsNull()); mj_deleteModel(model); } TEST_F(XMLReaderTest, IncludeAssetsTest) { static constexpr char xml[] = R"( )"; static constexpr char assets[] = R"( )"; static constexpr char subassets[] = R"( )"; mjVFS vfs; mj_defaultVFS(&vfs); mj_addBufferVFS(&vfs, "assets/tiny.png", kTinyPng, sizeof(kTinyPng)); mj_addBufferVFS(&vfs, "assets/subassets/subtiny.png", kTinyPng, sizeof(kTinyPng)); mj_addBufferVFS(&vfs, "assets/subassets/cube.obj", kTinyObj, sizeof(kTinyObj)); mj_addBufferVFS(&vfs, "assets/assets.xml", assets, sizeof(assets)); mj_addBufferVFS(&vfs, "assets/subassets/assets.xml", subassets, sizeof(subassets)); mj_addBufferVFS(&vfs, "model.xml", xml, sizeof(xml)); // loading the file should be successful std::array error; mjModel* model = mj_loadXML("model.xml", &vfs, error.data(), error.size()); ASSERT_THAT(model, NotNull()) << error.data(); mj_deleteModel(model); mj_deleteVFS(&vfs); } TEST_F(XMLReaderTest, FallbackIncludeAssetsTest) { static constexpr char xml[] = R"( )"; static constexpr char assets[] = R"( )"; static constexpr char subassets[] = R"( )"; mjVFS vfs; mj_defaultVFS(&vfs); mj_addBufferVFS(&vfs, "assets/tiny.png", kTinyPng, sizeof(kTinyPng)); // need to fallback for backwards compatibility mj_addBufferVFS(&vfs, "subtiny.png", kTinyPng, sizeof(kTinyPng)); mj_addBufferVFS(&vfs, "assets/assets.xml", assets, sizeof(assets)); mj_addBufferVFS(&vfs, "assets/subassets/assets.xml", subassets, sizeof(subassets)); mj_addBufferVFS(&vfs, "model.xml", xml, sizeof(xml)); // loading the file should be successful std::array error; mjModel* model = mj_loadXML("model.xml", &vfs, error.data(), error.size()); ASSERT_THAT(model, NotNull()) << error.data(); mj_deleteModel(model); mj_deleteVFS(&vfs); } TEST_F(XMLReaderTest, IncludeAbsoluteTest) { static constexpr char xml[] = R"( )"; static constexpr char assets[] = R"( )"; static constexpr char subassets[] = R"( )"; MockFilesystem fs("IncludeAbsoluteTest"); fs.AddFile("assets/tiny.png", kTinyPng, sizeof(kTinyPng)); fs.AddFile("assets/subtiny.png", kTinyPng, sizeof(kTinyPng)); fs.AddFile("assets/assets.xml", (const unsigned char*) assets, sizeof(assets)); fs.AddFile("assets/subassets/assets.xml", (const unsigned char*) subassets, sizeof(subassets)); fs.AddFile("model.xml", (const unsigned char*) xml, sizeof(xml)); std::string modelpath = fs.FullPath("model.xml"); std::array error; // loading the file should be successful mjModel* model = mj_loadXML(modelpath.c_str(), nullptr, error.data(), error.size()); ASSERT_THAT(model, NotNull()) << error.data(); mj_deleteModel(model); } TEST_F(XMLReaderTest, IncludeAbsoluteMeshDirTest) { static constexpr char xml[] = R"( )"; static constexpr char assets[] = R"( )"; static constexpr char cube[] = R"( v -0.500000 -0.500000 0.500000 v 0.500000 -0.500000 0.500000 v -0.500000 0.500000 0.500000 v 0.500000 0.500000 0.500000 v -0.500000 0.500000 -0.500000 v 0.500000 0.500000 -0.500000 v -0.500000 -0.500000 -0.500000 v 0.500000 -0.500000 -0.500000)"; MockFilesystem fs("IncludeAbsoluteMeshDirTest"); fs.AddFile("/assets/cube.obj", (const unsigned char*) cube, sizeof(cube)); fs.AddFile("assets.xml", (const unsigned char*) assets, sizeof(assets)); fs.AddFile("model.xml", (const unsigned char*) xml, sizeof(xml)); std::string modelpath = fs.FullPath("model.xml"); std::array error; // loading the file should be successful mjModel* model = mj_loadXML(modelpath.c_str(), nullptr, error.data(), error.size()); ASSERT_THAT(model, NotNull()) << error.data(); mj_deleteModel(model); } TEST_F(XMLReaderTest, ParsePolycoef) { static constexpr char xml[] = R"( )"; std::array error; mjModel* m = LoadModelFromString(xml, error.data(), error.size()); EXPECT_THAT(m, NotNull()) << error.data(); EXPECT_THAT(AsVector(m->eq_data + 0*mjNEQDATA, 5), ElementsAre(0, 1, 0, 0, 0)); EXPECT_THAT(AsVector(m->eq_data + 1*mjNEQDATA, 5), ElementsAre(2, 1, 0, 0, 0)); EXPECT_THAT(AsVector(m->eq_data + 2*mjNEQDATA, 5), ElementsAre(3, 4, 0, 0, 0)); EXPECT_THAT(AsVector(m->eq_data + 3*mjNEQDATA, 5), ElementsAre(5, 6, 7, 8, 9)); mj_deleteModel(m); } TEST_F(XMLReaderTest, TendonArmature) { static constexpr char xml[] = R"( )"; std::array error; mjModel* m = LoadModelFromString(xml, error.data(), error.size()); EXPECT_THAT(m, NotNull()) << error.data(); EXPECT_EQ(m->ntendon, 3); EXPECT_FLOAT_EQ(m->tendon_armature[0], 1.5); EXPECT_FLOAT_EQ(m->tendon_armature[1], 2.5); EXPECT_FLOAT_EQ(m->tendon_armature[2], 0); mj_deleteModel(m); } TEST_F(XMLReaderTest, TendonArmatureNegative) { static constexpr char xml[] = R"( )"; std::array error; mjModel* m = LoadModelFromString(xml, error.data(), error.size()); EXPECT_THAT(m, IsNull()); EXPECT_THAT(error.data(), HasSubstr("tendon armature cannot be negative")); } TEST_F(XMLReaderTest, TendonArmatureGeomWrap) { static constexpr char xml[] = R"( )"; std::array error; mjModel* m = LoadModelFromString(xml, error.data(), error.size()); EXPECT_THAT(m, IsNull()); EXPECT_THAT(error.data(), HasSubstr("geom wrapping not supported")); } // ------------------------ test frame parsing --------------------------------- TEST_F(XMLReaderTest, ParseFrame) { static constexpr char xml[] = R"( )"; std::array error; mjModel* m = LoadModelFromString(xml, error.data(), error.size()); EXPECT_THAT(m, NotNull()) << error.data(); EXPECT_THAT(m->geom_size[ 0], .5); EXPECT_THAT(m->geom_size[ 3], .6); EXPECT_THAT(m->geom_size[ 6], .1); EXPECT_THAT(m->geom_size[ 9], .2); EXPECT_THAT(m->geom_size[12], .3); mj_deleteModel(m); } TEST_F(XMLReaderTest, DuplicateFrameName) { static constexpr char xml[] = R"( )"; std::array error; mjModel* m = LoadModelFromString(xml, error.data(), error.size()); EXPECT_THAT(m, IsNull()) << error.data(); EXPECT_THAT(error.data(), HasSubstr("repeated name 'frame1'")); } // ---------------------- test replicate parsing ------------------------------- TEST_F(XMLReaderTest, ParseReplicate) { static constexpr char xml[] = R"( )"; std::array error; mjModel* m = LoadModelFromString(xml, error.data(), error.size()); EXPECT_THAT(m, testing::NotNull()) << error.data(); EXPECT_THAT(m->ngeom, 105); EXPECT_THAT(m->nsensor, 4); EXPECT_THAT(m->nbody, 102); // check that the separator is used correctly for (int i = 0; i < 2; ++i) { for (int j = 0; j < 2; ++j) { char geom_name[mjMAXUINAME] = ""; util::strcat_arr(geom_name, m->names + m->name_geomadr[2*i+j]); EXPECT_THAT(m->geom_pos[6*i+3*j+0], i); EXPECT_THAT(m->geom_pos[6*i+3*j+1], j); EXPECT_THAT(m->geom_pos[6*i+3*j+2], 1); EXPECT_THAT(std::string(geom_name), "geom_" + std::to_string(j) + std::to_string(i)); } } // check that 3 digits are used if count > 99 for (int i = 0; i < 2; ++i) { for (int j = 0; j < 10; ++j) { for (int k = 0; k < 10; ++k) { int ngeom = 100*i+10*j+k; if (ngeom > 99) break; char geom_name[mjMAXUINAME] = ""; util::strcat_arr(geom_name, m->names + m->name_geomadr[4+ngeom]); EXPECT_THAT( std::string(geom_name), "g" + std::to_string(i) + std::to_string(j) + std::to_string(k)); } } } // check body positions mjtNum pos[2] = {0, 0}; for (int i = 1; i < 102; ++i) { mjtNum theta = (i-1) * 1.8 * mjPI / 180; EXPECT_NEAR(m->body_pos[3*i+0], pos[0] + sin(theta), 1e-8) << i; EXPECT_NEAR(m->body_pos[3*i+1], pos[1] - cos(theta), 1e-8) << i; EXPECT_NEAR(m->body_pos[3*i+2], (i-1) * .1, 1e-8); pos[0] += 3 * cos(theta); pos[1] += 3 * sin(theta); } // check that the final pose is correct int n = m->nbody-1; EXPECT_NEAR(m->body_quat[4*n+0], 0, 1e-8); EXPECT_EQ(m->body_quat[4*n+1], 0); EXPECT_EQ(m->body_quat[4*n+2], 0); EXPECT_EQ(m->body_quat[4*n+3], 1); // check that the keyframe is resized EXPECT_THAT(m->nkey, 102); EXPECT_THAT(m->nq, 101); for (int i = 0; i < m->nkey; i++) { for (int j = 0; j < m->nq; j++) { EXPECT_THAT(m->key_qpos[i*m->nq+j], i == j ? 1 : 0) << i << " " << j; } } mj_deleteModel(m); } TEST_F(XMLReaderTest, ParseReplicatePartialReference) { static constexpr char xml[] = R"( )"; std::array error; mjModel* m = LoadModelFromString(xml, error.data(), error.size()); EXPECT_THAT(m, testing::NotNull()) << error.data(); EXPECT_THAT(m->nbody, 3); EXPECT_THAT(m->ngeom, 3); EXPECT_THAT(m->npair, 2); EXPECT_THAT(m->nexclude, 2); EXPECT_THAT(m->ntendon, 2); EXPECT_THAT(m->nsensor, 2); mj_deleteModel(m); } TEST_F(XMLReaderTest, ParseReplicateDefaultPropagate) { static constexpr char xml[] = R"( )"; std::array error; mjSpec* spec = mj_parseXMLString(xml, 0, error.data(), error.size()); EXPECT_THAT(spec, NotNull()) << error.data(); mjsBody* torso = mjs_findBody(spec, "torso-0"); EXPECT_THAT(torso, NotNull()); mjsDefault* def = mjs_getDefault(torso->element); EXPECT_THAT(def, NotNull()); EXPECT_THAT(def->geom->type, mjGEOM_CAPSULE); mjsBody* head = mjs_findBody(spec, "head-0"); EXPECT_THAT(head, NotNull()); def = mjs_getDefault(head->element); EXPECT_THAT(def, NotNull()); EXPECT_THAT(def->geom->type, mjGEOM_CAPSULE); mj_deleteSpec(spec); } TEST_F(XMLReaderTest, ParseReplicateRepeatedName) { static constexpr char xml[] = R"( )"; std::array error; mjSpec* spec = mj_parseXMLString(xml, 0, error.data(), error.size()); EXPECT_THAT(spec, IsNull()) << error.data(); EXPECT_THAT(error.data(), HasSubstr("repeated name 'b' in actuator")); EXPECT_THAT(error.data(), HasSubstr("Element 'replicate'")); } TEST_F(XMLReaderTest, RepeatedPrefix) { static constexpr char parent[] = R"( )"; static constexpr char child_1[] = R"( )"; static constexpr char child_2[] = R"( )"; auto vfs = std::make_unique(); mj_defaultVFS(vfs.get()); mj_addBufferVFS(vfs.get(), "child_1.xml", child_1, sizeof(child_1)); mj_addBufferVFS(vfs.get(), "child_2.xml", child_2, sizeof(child_2)); std::array err; mjSpec* c2 = mj_parseXMLString(child_2, 0, err.data(), err.size()); EXPECT_THAT(c2, NotNull()) << err.data(); mjSpec* c1 = mj_parseXMLString(child_1, vfs.get(), err.data(), err.size()); EXPECT_THAT(c1, NotNull()) << err.data(); mj_deleteSpec(c1); mj_deleteSpec(c2); mjSpec* spec = mj_parseXMLString(parent, vfs.get(), err.data(), err.size()); EXPECT_THAT(spec, IsNull()); EXPECT_THAT(err.data(), HasSubstr("mismatched parents")); mj_deleteSpec(spec); mj_deleteVFS(vfs.get()); } TEST_F(XMLReaderTest, ParseReplicateExcludeTendon) { static constexpr char xml[] = R"( )"; std::array error; mjSpec* spec = mj_parseXMLString(xml, 0, error.data(), error.size()); EXPECT_THAT(spec, NotNull()) << error.data(); mjModel* m = mj_compile(spec, 0); EXPECT_THAT(m, NotNull()); EXPECT_THAT(m->nbody, 67); EXPECT_THAT(m->ngeom, 66); EXPECT_THAT(m->nsite, 6); EXPECT_THAT(m->nu, 1); EXPECT_THAT(m->ntendon, 1); mj_deleteModel(m); mj_deleteSpec(spec); } TEST_F(XMLReaderTest, ParseReplicateWithTendon) { static constexpr char xml[] = R"( )"; std::array error; mjSpec* spec = mj_parseXMLString(xml, 0, error.data(), error.size()); EXPECT_THAT(spec, NotNull()) << error.data(); mjModel* m = mj_compile(spec, 0); EXPECT_THAT(m, NotNull()) << mjs_getError(spec); EXPECT_THAT(m->nbody, 25); EXPECT_THAT(m->ngeom, 24); EXPECT_THAT(m->nsite, 48); EXPECT_THAT(m->nu, 16); EXPECT_THAT(m->ntendon, 8); mj_deleteModel(m); mj_deleteSpec(spec); } // ---------------------- test spec assets parsing ----------------------------- TEST_F(XMLReaderTest, ParseSpecAssets) { std::array er; static const char* const kParentPath = "xml/testdata/parent.xml"; static const char* const kChildPath = "xml/testdata/child.xml"; const std::string xml_parent = GetTestDataFilePath(kParentPath); const std::string xml_child = GetTestDataFilePath(kChildPath); mjModel* parent = mj_loadXML(xml_parent.c_str(), 0, er.data(), er.size()); EXPECT_THAT(parent, NotNull()) << er.data(); mjModel* child = mj_loadXML(xml_child.c_str(), 0, er.data(), er.size()); EXPECT_THAT(child, NotNull()) << er.data(); mj_deleteModel(parent); mj_deleteModel(child); } TEST_F(XMLReaderTest, AttachSpecAssets) { static constexpr char xml_parent[] = R"( )"; static constexpr char xml_child[] = R"( )"; static constexpr char xml_expected[] = R"( )"; auto vfs = std::make_unique(); mj_defaultVFS(vfs.get()); mj_addBufferVFS(vfs.get(), "xml_child.xml", xml_child, sizeof(xml_child)); std::array er; mjModel* model = LoadModelFromString(xml_parent, er.data(), er.size(), vfs.get()); EXPECT_THAT(model, NotNull()) << er.data(); mjModel* expected = LoadModelFromString(xml_expected, er.data(), er.size()); EXPECT_THAT(expected, NotNull()) << er.data(); mjtNum tol = 0; std::string field = ""; EXPECT_LE(CompareModel(model, expected, field), tol) << "Expected and attached models are different!\n" << "Different field: " << field << '\n';; mj_deleteModel(model); mj_deleteModel(expected); mj_deleteVFS(vfs.get()); } TEST_F(XMLReaderTest, InvalidAttach) { static constexpr char xml_parent[] = R"( )"; static constexpr char xml_child[] = R"( )"; auto vfs = std::make_unique(); mj_defaultVFS(vfs.get()); mj_addBufferVFS(vfs.get(), "child.xml", xml_child, sizeof(xml_child)); std::array er; mjModel* model = LoadModelFromString(xml_parent, er.data(), er.size(), vfs.get()); EXPECT_THAT(model, IsNull()) << er.data(); EXPECT_THAT(er.data(), HasSubstr("repeated name '_actuator' in actuator")); EXPECT_THAT(er.data(), HasSubstr("Element 'attach'")); mj_deleteVFS(vfs.get()); } TEST_F(XMLReaderTest, LookupCompilerOptionWithoutSpecCopy) { static constexpr char child_xml[] = R"( )"; static constexpr char parent_xml[] = R"( )"; auto vfs = std::make_unique(); mj_defaultVFS(vfs.get()); mj_addBufferVFS(vfs.get(), "child.xml", child_xml, sizeof(child_xml)); mj_addBufferVFS(vfs.get(), "parent.xml", parent_xml, sizeof(parent_xml)); std::array error; auto* spec = mj_parseXMLString(parent_xml, vfs.get(), error.data(), error.size()); ASSERT_THAT(spec, NotNull()) << error.data(); mjModel* model = mj_compile(spec, vfs.get()); EXPECT_THAT(model, NotNull()); EXPECT_THAT(model->njnt, 2); EXPECT_NEAR(model->jnt_range[0], -3.14159, 1e-5); EXPECT_NEAR(model->jnt_range[1], 3.14159, 1e-5); EXPECT_NEAR(model->jnt_range[2], -3.14159, 1e-5); EXPECT_NEAR(model->jnt_range[3], 3.14159, 1e-5); mjSpec* copied_spec = mj_copySpec(spec); ASSERT_THAT(copied_spec, NotNull()); mjModel* copied_model = mj_compile(copied_spec, vfs.get()); EXPECT_THAT(copied_model, NotNull()); EXPECT_THAT(copied_model->njnt, 2); EXPECT_NEAR(copied_model->jnt_range[0], -3.14159, 1e-5); EXPECT_NEAR(copied_model->jnt_range[1], 3.14159, 1e-5); EXPECT_NEAR(copied_model->jnt_range[2], -3.14159, 1e-5); EXPECT_NEAR(copied_model->jnt_range[3], 3.14159, 1e-5); mj_deleteSpec(spec); mj_deleteSpec(copied_spec); mj_deleteModel(model); mj_deleteModel(copied_model); mj_deleteVFS(vfs.get()); } // ----------------------- test camera parsing --------------------------------- TEST_F(XMLReaderTest, CameraInvalidFovyAndSensorsize) { static constexpr char xml[] = R"( )"; std::array error; mjModel* m = LoadModelFromString(xml, error.data(), error.size()); EXPECT_THAT(m, IsNull()); EXPECT_THAT(error.data(), HasSubstr("either 'fovy' or 'sensorsize'")); EXPECT_THAT(error.data(), HasSubstr("line 6")); } TEST_F(XMLReaderTest, CameraPrincipalRequiresSensorsize) { static constexpr char xml[] = R"( )"; std::array error; mjModel* m = LoadModelFromString(xml, error.data(), error.size()); EXPECT_THAT(m, IsNull()); EXPECT_THAT(error.data(), HasSubstr("attribute missing: 'sensorsize'")); EXPECT_THAT(error.data(), HasSubstr("line 6")); } TEST_F(XMLReaderTest, CameraSensorsizeRequiresResolution) { static constexpr char xml[] = R"( )"; std::array error; mjModel* m = LoadModelFromString(xml, error.data(), error.size()); EXPECT_THAT(m, IsNull()); EXPECT_THAT(error.data(), HasSubstr("attribute missing: 'resolution'")); EXPECT_THAT(error.data(), HasSubstr("line 6")); } // ----------------------- test inertia parsing -------------------------------- TEST_F(XMLReaderTest, InvalidInertialOrientation) { static constexpr char xml[] = R"( )"; std::array error; mjModel* model = LoadModelFromString(xml, error.data(), error.size()); ASSERT_THAT(model, IsNull()); EXPECT_THAT( error.data(), HasSubstr( "fullinertia and inertial orientation cannot both be specified")); } TEST_F(XMLReaderTest, ReadShellParameter) { static constexpr char xml[] = R"( )"; std::array error; mjModel* model = LoadModelFromString(xml, error.data(), error.size()); ASSERT_THAT(model, NotNull()); mj_deleteModel(model); } TEST_F(XMLReaderTest, ReadsSkinGroups) { static constexpr char xml[] = R"( )"; std::array error; mjModel* model = LoadModelFromString(xml, error.data(), error.size()); ASSERT_THAT(model, NotNull()); int flexid1 = mj_name2id(model, mjOBJ_FLEX, "B0"); int flexid2 = mj_name2id(model, mjOBJ_FLEX, "B1"); EXPECT_THAT(model->flex_group[flexid1], 2); EXPECT_THAT(model->skin_group[0], 4); EXPECT_THAT(model->flex_group[flexid2], 4); EXPECT_THAT(model->skin_group[1], 2); mj_deleteModel(model); } TEST_F(XMLReaderTest, InvalidSkinGroup) { static constexpr char xml[] = R"( )"; std::array error; mjModel* model = LoadModelFromString(xml, error.data(), error.size()); EXPECT_THAT(model, IsNull()); EXPECT_THAT( error.data(), HasSubstr("skin group must be between 0 and 5\nElement 'skin', line 7")); } TEST_F(XMLReaderTest, Orthographic) { static constexpr char xml[] = R"( )"; std::array error; mjModel* model = LoadModelFromString(xml, error.data(), error.size()); EXPECT_THAT(model, NotNull()) << error.data(); EXPECT_EQ(model->vis.global.orthographic, 1); EXPECT_EQ(model->cam_orthographic[0], 1); EXPECT_EQ(model->cam_orthographic[1], 1); EXPECT_EQ(model->cam_fovy[0], 1); EXPECT_EQ(model->cam_fovy[1], 2); mj_deleteModel(model); } // ------------- test height-field parsing ------------------------------------- using HfieldParsingTest = MujocoTest; TEST_F(HfieldParsingTest, NoData) { static constexpr char xml[] = R"( )"; std::array error; mjModel* model = LoadModelFromString(xml, error.data(), error.size()); EXPECT_THAT(model, NotNull()) << error.data(); EXPECT_EQ(model->hfield_nrow[0], 4); EXPECT_EQ(model->hfield_ncol[0], 3); EXPECT_EQ(model->hfield_size[0], 0.5); EXPECT_EQ(model->hfield_size[1], 0.5); EXPECT_EQ(model->hfield_size[2], 1); EXPECT_EQ(model->hfield_size[3], 0.1); mj_deleteModel(model); } TEST_F(HfieldParsingTest, HasDataBadSize) { static constexpr char xml[] = R"( )"; std::array error; mjModel* model = LoadModelFromString(xml, error.data(), error.size()); EXPECT_THAT(model, IsNull()); EXPECT_THAT(error.data(), HasSubstr("data length must match nrow*ncol")); EXPECT_THAT(error.data(), HasSubstr("line 4")); } TEST_F(HfieldParsingTest, HasData) { static constexpr char xml[] = R"( )"; std::array error; mjModel* model = LoadModelFromString(xml, error.data(), error.size()); EXPECT_THAT(model, NotNull()) << error.data(); EXPECT_EQ(model->hfield_nrow[0], 3); EXPECT_EQ(model->hfield_ncol[0], 2); EXPECT_EQ(model->hfield_size[0], 0.5); EXPECT_EQ(model->hfield_size[1], 0.5); EXPECT_EQ(model->hfield_size[2], 1); EXPECT_EQ(model->hfield_size[3], 0.1); // offset (minimum) and scaling (maximum) from normalizing operation float offset = 1.0; float scale = 6.0 - offset; // compare data, note: reverse row order EXPECT_THAT(model->hfield_data[0], FloatEq((5-offset)/scale)); EXPECT_THAT(model->hfield_data[1], FloatEq((6-offset)/scale)); EXPECT_THAT(model->hfield_data[2], FloatEq((3-offset)/scale)); EXPECT_THAT(model->hfield_data[3], FloatEq((4-offset)/scale)); EXPECT_THAT(model->hfield_data[4], FloatEq((1-offset)/scale)); EXPECT_THAT(model->hfield_data[5], FloatEq((2-offset)/scale)); mj_deleteModel(model); } // ------------- test relative frame sensor parsing ---------------------------- using RelativeFrameSensorParsingTest = MujocoTest; TEST_F(RelativeFrameSensorParsingTest, RefNameButNoType) { static constexpr char xml[] = R"( )"; std::array error; LoadModelFromString(xml, error.data(), error.size()); EXPECT_THAT(error.data(), HasSubstr("but reftype is missing")); EXPECT_THAT(error.data(), HasSubstr("line 8")); } TEST_F(RelativeFrameSensorParsingTest, RefTypeButNoName) { static constexpr char xml[] = R"( )"; std::array error; LoadModelFromString(xml, error.data(), error.size()); EXPECT_THAT(error.data(), HasSubstr("attribute missing: 'refname'")); EXPECT_THAT(error.data(), HasSubstr("line 8")); } // ------------- test actlimited parsing --------------------------------------- using ActuatorTest = MujocoTest; TEST_F(ActuatorTest, InvalidActlimited) { static constexpr char xml[] = R"( )"; std::array error; mjModel* model = LoadModelFromString(xml, error.data(), error.size()); ASSERT_THAT(model, IsNull()); EXPECT_THAT(error.data(), HasSubstr("unrecognized attribute")); EXPECT_THAT(error.data(), HasSubstr("line 10")); } TEST_F(ActuatorTest, IncompleteActlimited) { static constexpr char xml[] = R"( )"; std::array error; mjModel* model = LoadModelFromString(xml, error.data(), error.size()); ASSERT_THAT(model, IsNull()); EXPECT_THAT(error.data(), HasSubstr("attribute 'actrange' does not have enough data")); } TEST_F(ActuatorTest, ReadsByte) { static constexpr char xml[] = R"( )"; std::array error; mjModel* model = LoadModelFromString(xml, error.data(), error.size()); ASSERT_THAT(model, NotNull()); EXPECT_EQ(*(model->actuator_actlimited), (mjtByte)(1 & 0xFF)); mj_deleteModel(model); } // ---------------- test actuator parsing -------------------------------------- using ActuatorParseTest = MujocoTest; TEST_F(ActuatorParseTest, PositionTimeconst) { static constexpr char xml[] = R"( )"; std::array error; mjModel* model = LoadModelFromString(xml, error.data(), error.size()); ASSERT_THAT(model, NotNull()); ASSERT_NEAR(model->actuator_dynprm[0], 2.0, 1e-6); EXPECT_THAT(model->actuator_dyntype[0], Eq(mjDYN_FILTEREXACT)); mj_deleteModel(model); } TEST_F(ActuatorParseTest, PositionTimeconstInheritrange) { static constexpr char xml[] = R"( )"; std::array error; mjModel* model = LoadModelFromString(xml, error.data(), error.size()); ASSERT_THAT(model, NotNull()); mj_deleteModel(model); } TEST_F(ActuatorParseTest, PositionTimeconstDefault) { static constexpr char xml[] = R"( )"; std::array error; mjModel* model = LoadModelFromString(xml, error.data(), error.size()); ASSERT_THAT(model, NotNull()); ASSERT_NEAR(model->actuator_dynprm[0], 1.0, 1e-6); EXPECT_THAT(model->actuator_dyntype[0], Eq(mjDYN_FILTEREXACT)); mj_deleteModel(model); } TEST_F(ActuatorParseTest, PositionTimeconstDefaultOverride) { static constexpr char xml[] = R"( )"; std::array error; mjModel* model = LoadModelFromString(xml, error.data(), error.size()); ASSERT_THAT(model, NotNull()); EXPECT_FALSE(model->actuator_dynprm[0]); EXPECT_THAT(model->actuator_dyntype[0], Eq(mjDYN_NONE)); mj_deleteModel(model); } TEST_F(ActuatorParseTest, ReadsDamper) { static constexpr char xml[] = R"( )"; std::array error; mjModel* model = LoadModelFromString(xml, error.data(), error.size()); ASSERT_THAT(model, NotNull()); EXPECT_THAT(model->actuator_gaintype[0], Eq(mjGAIN_AFFINE)); EXPECT_THAT(model->actuator_gaintype[1], Eq(mjGAIN_AFFINE)); EXPECT_THAT(model->actuator_biastype[0], Eq(mjBIAS_NONE)); EXPECT_THAT(model->actuator_biastype[1], Eq(mjBIAS_NONE)); mj_deleteModel(model); } TEST_F(ActuatorParseTest, DamperRequiresPositiveDamping) { static constexpr char xml[] = R"( )"; std::array error; mjModel* model = LoadModelFromString(xml, error.data(), error.size()); ASSERT_THAT(model, IsNull()); EXPECT_THAT(error.data(), HasSubstr("damping coefficient cannot be negative")); } TEST_F(ActuatorParseTest, DamperRequiresControlRange) { static constexpr char xml[] = R"( )"; std::array error; mjModel* model = LoadModelFromString(xml, error.data(), error.size()); ASSERT_THAT(model, IsNull()); EXPECT_THAT(error.data(), HasSubstr("invalid control range")); EXPECT_THAT(error.data(), HasSubstr("line 10")); } TEST_F(ActuatorParseTest, DamperPositiveControlRange) { static constexpr char xml[] = R"( )"; std::array error; mjModel* model = LoadModelFromString(xml, error.data(), error.size()); ASSERT_THAT(model, IsNull()); EXPECT_THAT(error.data(), HasSubstr("control range cannot be negative")); EXPECT_THAT(error.data(), HasSubstr("line 10")); } TEST_F(ActuatorParseTest, ReadsPositionIntvelKv) { static constexpr char xml[] = R"( )"; std::array error; mjModel* model = LoadModelFromString(xml, error.data(), error.size()); ASSERT_THAT(model, NotNull()); EXPECT_THAT(model->actuator_biasprm[0*mjNBIAS + 2], Eq(-2.0)); EXPECT_THAT(model->actuator_biasprm[1*mjNBIAS + 2], Eq(-3.0)); mj_deleteModel(model); } TEST_F(ActuatorParseTest, RequirePositiveKv) { static constexpr char xml[] = R"( )"; std::array error; mjModel* model = LoadModelFromString(xml, error.data(), error.size()); ASSERT_THAT(model, IsNull()); EXPECT_THAT(error.data(), HasSubstr("kv cannot be negative")); EXPECT_THAT(error.data(), HasSubstr("line 10")); } TEST_F(ActuatorParseTest, PositionIntvelocityVelocityDefaultsPropagate) { static constexpr char xml[] = R"( )"; std::array error; mjModel* model = LoadModelFromString(xml, error.data(), error.size()); ASSERT_THAT(model, NotNull()) << error.data(); EXPECT_EQ(model->actuator_gainprm[0*mjNGAIN + 0], 3.0); EXPECT_EQ(model->actuator_biasprm[0*mjNBIAS + 1], -3.0); EXPECT_EQ(model->actuator_biasprm[0*mjNBIAS + 2], -4.0); EXPECT_EQ(model->actuator_gainprm[1*mjNGAIN + 0], 5.0); EXPECT_EQ(model->actuator_biasprm[1*mjNBIAS + 1], -5.0); EXPECT_EQ(model->actuator_biasprm[1*mjNBIAS + 2], -6.0); EXPECT_EQ(model->actuator_gainprm[2*mjNGAIN + 0], 7.0); EXPECT_EQ(model->actuator_biasprm[2*mjNBIAS + 1], 0.0); EXPECT_EQ(model->actuator_biasprm[2*mjNBIAS + 2], -7.0); for (int i = 0; i < model->nu; i++) { for (int j = 3; j < mjNBIAS; j++) { EXPECT_EQ(model->actuator_biasprm[i*mjNBIAS + j], 0.0); } for (int j = 3; j < mjNGAIN; j++) { EXPECT_EQ(model->actuator_gainprm[i*mjNGAIN + j], 0.0); } } EXPECT_EQ(model->actuator_ctrlrange[0*2 + 0], -1.0); EXPECT_EQ(model->actuator_ctrlrange[0*2 + 1], 3.0); EXPECT_EQ(model->actuator_actrange[1*2 + 0], 0.5); EXPECT_EQ(model->actuator_actrange[1*2 + 1], 1.5); mj_deleteModel(model); } TEST_F(ActuatorParseTest, IntvelocityCheckEquivalence) { static constexpr char xml[] = R"( )"; std::array error; mjModel* model = LoadModelFromString(xml, error.data(), error.size()); ASSERT_THAT(model, NotNull()); // same actlimited EXPECT_EQ(model->actuator_actlimited[0], 1); EXPECT_EQ(model->actuator_actlimited[1], 1); // same dyntype EXPECT_EQ(model->actuator_dyntype[0], mjDYN_INTEGRATOR); EXPECT_EQ(model->actuator_dyntype[1], mjDYN_INTEGRATOR); // same biastype EXPECT_EQ(model->actuator_biastype[0], mjBIAS_AFFINE); EXPECT_EQ(model->actuator_biastype[1], mjBIAS_AFFINE); // same gaintype EXPECT_EQ(model->actuator_gaintype[0], mjGAIN_FIXED); EXPECT_EQ(model->actuator_gaintype[1], mjGAIN_FIXED); // same gainprm EXPECT_DOUBLE_EQ(model->actuator_gainprm[0], 2.5); EXPECT_DOUBLE_EQ(model->actuator_gainprm[mjNGAIN], 2.5); // same biasprm EXPECT_DOUBLE_EQ(model->actuator_biasprm[0], 0.0); EXPECT_DOUBLE_EQ(model->actuator_biasprm[1], -2.5); EXPECT_DOUBLE_EQ(model->actuator_biasprm[2], 0.0); EXPECT_DOUBLE_EQ(model->actuator_biasprm[mjNBIAS], 0.0); EXPECT_DOUBLE_EQ(model->actuator_biasprm[mjNBIAS + 1], -2.5); EXPECT_DOUBLE_EQ(model->actuator_biasprm[mjNBIAS + 2], 0.0); // same actrange EXPECT_DOUBLE_EQ(model->actuator_actrange[0 + 0], -1.57); EXPECT_DOUBLE_EQ(model->actuator_actrange[0 + 1], 1.57); EXPECT_DOUBLE_EQ(model->actuator_actrange[0 + 2], -1.57); EXPECT_DOUBLE_EQ(model->actuator_actrange[0 + 3], 1.57); mj_deleteModel(model); } TEST_F(ActuatorParseTest, IntvelocityCheckDefaultsIfNotSpecified) { static constexpr char xml[] = R"( )"; std::array error; mjModel* model = LoadModelFromString(xml, error.data(), error.size()); ASSERT_THAT(model, NotNull()); // check that by default kp = 1 EXPECT_DOUBLE_EQ(model->actuator_gainprm[0], 1.0); // check that biasprm is (0, -1, 0) EXPECT_DOUBLE_EQ(model->actuator_biasprm[0], 0.0); EXPECT_DOUBLE_EQ(model->actuator_biasprm[1], -1.0); EXPECT_DOUBLE_EQ(model->actuator_biasprm[2], 0.0); mj_deleteModel(model); } TEST_F(ActuatorParseTest, IntvelocityNoActrangeThrowsError) { static constexpr char xml[] = R"( )"; std::array error; mjModel* model = LoadModelFromString(xml, error.data(), error.size()); ASSERT_THAT(model, IsNull()); EXPECT_THAT(error.data(), HasSubstr("invalid actrange for actuator")); EXPECT_THAT(error.data(), HasSubstr("line 10")); } TEST_F(ActuatorParseTest, IntvelocityDefaultsPropagate) { static constexpr char xml[] = R"( )"; std::array error; mjModel* model = LoadModelFromString(xml, error.data(), error.size()); ASSERT_THAT(model, NotNull()); EXPECT_DOUBLE_EQ(model->actuator_gainprm[0], 5); EXPECT_DOUBLE_EQ(model->actuator_gainprm[mjNGAIN], 1); EXPECT_DOUBLE_EQ(model->actuator_actrange[0 + 0], 0); EXPECT_DOUBLE_EQ(model->actuator_actrange[0 + 1], 1); EXPECT_DOUBLE_EQ(model->actuator_actrange[0 + 2], -1); EXPECT_DOUBLE_EQ(model->actuator_actrange[0 + 3], 1); mj_deleteModel(model); } TEST_F(ActuatorParseTest, AdhesionDefaultsPropagate) { static constexpr char xml[] = R"( )"; std::array error; mjModel* model = LoadModelFromString(xml, error.data(), error.size()); ASSERT_THAT(model, NotNull()); EXPECT_EQ(model->actuator_ctrlrange[0], 0); EXPECT_EQ(model->actuator_ctrlrange[1], 3); mj_deleteModel(model); } TEST_F(ActuatorParseTest, ErrorBadAdhesionDefaults) { static constexpr char xml[] = R"( )"; std::array error; mjModel* model = LoadModelFromString(xml, error.data(), error.size()); ASSERT_THAT(model, IsNull()); EXPECT_THAT(error.data(), HasSubstr("adhesion control range cannot be negative")); } // make sure range requirement is not enforced at parse time TEST_F(ActuatorParseTest, DampersDontRequireRange) { static constexpr char xml[] = R"( )"; std::array error; mjModel* model = LoadModelFromString(xml, error.data(), error.size()); ASSERT_THAT(model, NotNull()); EXPECT_EQ(model->actuator_ctrlrange[0], 0); EXPECT_EQ(model->actuator_ctrlrange[1], 2); mj_deleteModel(model); } // adhesion actuators inherit from general defaults TEST_F(ActuatorParseTest, AdhesionInheritsFromGeneral) { static constexpr char xml[] = R"( )"; std::array error; mjModel* model = LoadModelFromString(xml, error.data(), error.size()); ASSERT_THAT(model, NotNull()) << error.data(); // expect that gainprm was inherited from the general default EXPECT_EQ(model->actuator_gainprm[0], 5); // expect that dynprm was inherited from the general default EXPECT_EQ(model->actuator_dynprm[0], 123); // expect that dyntype was inherited from the general default EXPECT_EQ(model->actuator_dyntype[0], mjDYN_FILTER); mj_deleteModel(model); } TEST_F(ActuatorParseTest, ActdimDefaultsPropagate) { static constexpr char xml[] = R"( )"; std::array error; mjModel* model = LoadModelFromString(xml, error.data(), error.size()); ASSERT_THAT(model, NotNull()) << error.data(); // expect that actdim was inherited from the general default EXPECT_EQ(model->actuator_actnum[0], 2); mj_deleteModel(model); } TEST_F(ActuatorParseTest, MusclesParseSmoothdyn) { static constexpr char xml[] = R"( )"; std::array error; mjModel* model = LoadModelFromString(xml, error.data(), error.size()); ASSERT_THAT(model, NotNull()) << error.data(); EXPECT_EQ(model->actuator_dynprm[2], 0.0); EXPECT_EQ(model->actuator_dynprm[mjNDYN + 2], 0.4); mj_deleteModel(model); } TEST_F(ActuatorParseTest, MusclesSmoothdynNegative) { static constexpr char xml[] = R"( )"; std::array error; mjModel* model = LoadModelFromString(xml, error.data(), error.size()); ASSERT_THAT(model, IsNull()); EXPECT_THAT(error.data(), HasSubstr("muscle tausmooth cannot be negative")); EXPECT_THAT(error.data(), HasSubstr("line 10")); } TEST_F(ActuatorParseTest, GroupDisable) { static constexpr char xml[] = R"( )"; std::array error; mjModel* model = LoadModelFromString(xml, error.data(), error.size()); ASSERT_THAT(model, NotNull()); EXPECT_EQ(model->opt.disableactuator, (1<<0) + (1<<3) + (1<<8)); mj_deleteModel(model); } TEST_F(ActuatorParseTest, GroupDisableNegative) { static constexpr char xml[] = R"( )"; std::array error; mjModel* model = LoadModelFromString(xml, error.data(), error.size()); ASSERT_THAT(model, IsNull()); EXPECT_THAT(error.data(), HasSubstr("must be non-negative")); EXPECT_THAT(error.data(), HasSubstr("line 3")); } TEST_F(ActuatorParseTest, GroupDisableTooBig) { static constexpr char xml[] = R"( )"; std::array error; mjModel* model = LoadModelFromString(xml, error.data(), error.size()); ASSERT_THAT(model, IsNull()); EXPECT_THAT(error.data(), HasSubstr("cannot exceed 30")); EXPECT_THAT(error.data(), HasSubstr("line 3")); } // ------------- test sensor parsing ------------------------------------------- using SensorParseTest = MujocoTest; TEST_F(SensorParseTest, UserObjTypeNoName) { static constexpr char xml[] = R"( )"; std::array error; mjModel* model = LoadModelFromString(xml, error.data(), error.size()); ASSERT_THAT(model, IsNull()); EXPECT_THAT(error.data(), HasSubstr("objtype 'site' given but")); EXPECT_THAT(error.data(), HasSubstr("line 4")); } TEST_F(SensorParseTest, UserObjNameNoType) { static constexpr char xml[] = R"( )"; std::array error; mjModel* model = LoadModelFromString(xml, error.data(), error.size()); ASSERT_THAT(model, IsNull()); EXPECT_THAT(error.data(), HasSubstr("objname 'kevin' given but")); EXPECT_THAT(error.data(), HasSubstr("line 4")); } TEST_F(SensorParseTest, UserNeedstageAcc) { static constexpr char xml[] = R"( )"; std::array error; mjModel* model = LoadModelFromString(xml, error.data(), error.size()); ASSERT_THAT(model, NotNull()) << error.data(); EXPECT_EQ(model->sensor_needstage[0], mjSTAGE_VEL); EXPECT_EQ(model->sensor_needstage[1], mjSTAGE_ACC); EXPECT_EQ(model->sensor_needstage[2], mjSTAGE_POS); mj_deleteModel(model); } // ------------- test general parsing ------------------------------------------ TEST_F(XMLReaderTest, ZnearZeroNotAllowed) { static constexpr char xml[] = R"( )"; std::array error; mjModel* model = LoadModelFromString(xml, error.data(), error.size()); ASSERT_THAT(model, IsNull()); EXPECT_THAT(error.data(), HasSubstr("znear must be strictly positive")); EXPECT_THAT(error.data(), HasSubstr("line 4")); } TEST_F(XMLReaderTest, ZnearNegativeNotAllowed) { static constexpr char xml[] = R"( )"; std::array error; mjModel* model = LoadModelFromString(xml, error.data(), error.size()); ASSERT_THAT(model, IsNull()); EXPECT_THAT(error.data(), HasSubstr("znear must be strictly positive")); EXPECT_THAT(error.data(), HasSubstr("line 4")); } TEST_F(XMLReaderTest, ExtentZeroNotAllowed) { static constexpr char xml[] = R"( )"; std::array error; mjModel* model = LoadModelFromString(xml, error.data(), error.size()); ASSERT_THAT(model, IsNull()); EXPECT_THAT(error.data(), HasSubstr("extent must be strictly positive")); EXPECT_THAT(error.data(), HasSubstr("line 3")); } TEST_F(XMLReaderTest, ExtentNegativeNotAllowed) { static constexpr char xml[] = R"( )"; std::array error; mjModel* model = LoadModelFromString(xml, error.data(), error.size()); ASSERT_THAT(model, IsNull()); EXPECT_THAT(error.data(), HasSubstr("extent must be strictly positive")); EXPECT_THAT(error.data(), HasSubstr("line 3")); } TEST_F(XMLReaderTest, LightRadius) { static constexpr char xml[] = R"( )"; std::array error; mjModel* model = LoadModelFromString(xml, error.data(), error.size()); ASSERT_THAT(model, NotNull()) << error.data(); EXPECT_FLOAT_EQ(model->light_bulbradius[0], 0.02); EXPECT_FLOAT_EQ(model->light_bulbradius[1], 1); EXPECT_FLOAT_EQ(model->light_bulbradius[2], 2); mj_deleteModel(model); } } // namespace } // namespace mujoco