| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| |
|
| | |
| |
|
| | #include <cstddef> |
| | #include <string> |
| |
|
| | #include <gmock/gmock.h> |
| | #include <gtest/gtest.h> |
| | #include <mujoco/mjmodel.h> |
| | #include <mujoco/mujoco.h> |
| | #include "test/fixture.h" |
| |
|
| | namespace mujoco { |
| | namespace { |
| |
|
| | using ::testing::NotNull; |
| |
|
| | static const char* const kFramelessContactPath = |
| | "engine/testdata/collision_convex/frameless_contact.xml"; |
| | static const char* const kFramelessContactHfieldPath = |
| | "engine/testdata/collision_convex/frameless_contact_hfield.xml"; |
| | static const char* const kCylinderBoxPath = |
| | "engine/testdata/collision_convex/cylinder_box.xml"; |
| |
|
| | using MjcConvexTest = MujocoTest; |
| |
|
| | TEST_F(MjcConvexTest, FramelessContact) { |
| | const std::string xml_path = GetTestDataFilePath(kFramelessContactPath); |
| | char error[1024]; |
| | const std::size_t error_sz = 1024; |
| | mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, error, error_sz); |
| | |
| | EXPECT_THAT(model, NotNull()) << "Failed to load model: " << error; |
| | mj_deleteModel(model); |
| | } |
| |
|
| | TEST_F(MjcConvexTest, FramelessContactHfield) { |
| | const std::string xml_path = GetTestDataFilePath(kFramelessContactHfieldPath); |
| | char error[1024]; |
| | const std::size_t error_sz = 1024; |
| | mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, error, error_sz); |
| | |
| | EXPECT_THAT(model, NotNull()) << "Failed to load model: " << error; |
| | mj_deleteModel(model); |
| | } |
| |
|
| | TEST_F(MjcConvexTest, CylinderBox) { |
| | const std::string xml_path = GetTestDataFilePath(kCylinderBoxPath); |
| | mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, nullptr, 0); |
| | ASSERT_THAT(model, NotNull()); |
| | mjData* data = mj_makeData(model); |
| |
|
| | |
| | mj_forward(model, data); |
| | EXPECT_EQ(data->ncon, 5); |
| |
|
| | |
| | model->opt.enableflags &= ~mjENBL_MULTICCD; |
| | mj_forward(model, data); |
| | EXPECT_EQ(data->ncon, 1); |
| |
|
| | mj_deleteData(data); |
| | mj_deleteModel(model); |
| | } |
| |
|
| | } |
| | } |
| |
|