From 96c86a426f44e12fb680f521e6d8719bb52ce335 Mon Sep 17 00:00:00 2001 From: Michael Carroll Date: Tue, 9 Jan 2024 15:24:02 +0000 Subject: [PATCH] Use centralized library and constants Signed-off-by: Michael Carroll --- dartsim/CMakeLists.txt | 1 + src/CMakeLists.txt | 2 + src/Cloneable_TEST.cc | 2 +- src/CompositeData_TEST.cc | 2 +- src/FindFeatures_TEST.cc | 4 +- src/SpecifyData_TEST.cc | 2 +- test/CMakeLists.txt | 13 ++++ test/benchmark/CMakeLists.txt | 3 +- test/benchmark/ExpectData.cc | 2 +- test/common_test/CMakeLists.txt | 15 +---- test/common_test/added_mass.cc | 10 ++- test/common_test/addexternalforcetorque.cc | 12 ++-- test/common_test/basic_test.cc | 2 +- test/common_test/collisions.cc | 2 +- test/common_test/construct_empty_world.cc | 2 +- test/common_test/detachable_joint.cc | 9 ++- test/common_test/free_joint_features.cc | 13 ++-- test/common_test/joint_features.cc | 66 +++++-------------- .../joint_transmitted_wrench_features.cc | 5 +- test/common_test/kinematic_features.cc | 5 +- test/common_test/link_features.cc | 19 ++---- test/common_test/shape_features.cc | 13 ++-- test/common_test/simulation_features.cc | 33 ++++------ test/common_test/world_features.cc | 22 ++----- test/common_test/worlds/Worlds.hh | 54 +++++++++++++++ test/include/test/Utils.hh | 7 +- test/integration/CMakeLists.txt | 6 +- test/integration/CanReadWrite.cc | 2 +- test/integration/DoublePendulum.cc | 2 +- test/integration/FeatureSystem.cc | 2 +- test/integration/FrameSemantics.hh | 4 +- test/integration/JointTypes.hh | 4 +- test/integration/RequestFeatures.cc | 6 +- test/performance/CMakeLists.txt | 7 +- test/performance/ExpectData.cc | 2 +- tpe/plugin/CMakeLists.txt | 1 + 36 files changed, 172 insertions(+), 184 deletions(-) create mode 100644 test/common_test/worlds/Worlds.hh diff --git a/dartsim/CMakeLists.txt b/dartsim/CMakeLists.txt index a7c02449c..34824555b 100644 --- a/dartsim/CMakeLists.txt +++ b/dartsim/CMakeLists.txt @@ -84,6 +84,7 @@ gz_build_tests( LIB_DEPS ${features} ${dartsim_plugin} + gz-physics-test gz-plugin${GZ_PLUGIN_VER}::loader gz-common${GZ_COMMON_VER}::gz-common${GZ_COMMON_VER} gz-common${GZ_COMMON_VER}::geospatial diff --git a/src/CMakeLists.txt b/src/CMakeLists.txt index 70b50d48c..f29996912 100644 --- a/src/CMakeLists.txt +++ b/src/CMakeLists.txt @@ -25,6 +25,8 @@ endif() gz_build_tests( TYPE UNIT SOURCES ${gtest_sources} + LIB_DEPS + gz-physics-test ENVIRONMENT GZ_PHYSICS_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX} INCLUDE_DIRS diff --git a/src/Cloneable_TEST.cc b/src/Cloneable_TEST.cc index 29da50e69..db5766197 100644 --- a/src/Cloneable_TEST.cc +++ b/src/Cloneable_TEST.cc @@ -18,7 +18,7 @@ #include #include "gz/physics/Cloneable.hh" -#include "TestDataTypes.hh" +#include "test/TestDataTypes.hh" using namespace gz; using physics::Cloneable; diff --git a/src/CompositeData_TEST.cc b/src/CompositeData_TEST.cc index 232905f40..3a9e1a2b2 100644 --- a/src/CompositeData_TEST.cc +++ b/src/CompositeData_TEST.cc @@ -18,7 +18,7 @@ #include #include "gz/physics/CompositeData.hh" -#include "TestDataTypes.hh" +#include "test/TestDataTypes.hh" using namespace gz; diff --git a/src/FindFeatures_TEST.cc b/src/FindFeatures_TEST.cc index 165e3f42f..4309807ab 100644 --- a/src/FindFeatures_TEST.cc +++ b/src/FindFeatures_TEST.cc @@ -24,7 +24,7 @@ #include -#include "TestUtilities.hh" +#include "test/Utils.hh" using namespace gz; @@ -59,7 +59,7 @@ TEST(FindFeatures_TEST, ForwardStep) TEST(FindFeatures_TEST, Unimplemented) { using TestFeatures = - physics::FeatureList; + physics::FeatureList; plugin::Loader loader; PrimeTheLoader(loader); diff --git a/src/SpecifyData_TEST.cc b/src/SpecifyData_TEST.cc index 7593526f2..2018f2018 100644 --- a/src/SpecifyData_TEST.cc +++ b/src/SpecifyData_TEST.cc @@ -19,7 +19,7 @@ #define GZ_UNITTEST_EXPECTDATA_ACCESS -#include "TestDataTypes.hh" +#include "test/TestDataTypes.hh" #include "gz/physics/SpecifyData.hh" #include "gz/math/Vector3.hh" diff --git a/test/CMakeLists.txt b/test/CMakeLists.txt index 5e1e3e0ec..4e8811d7e 100644 --- a/test/CMakeLists.txt +++ b/test/CMakeLists.txt @@ -19,6 +19,19 @@ ExternalProject_Add( "-DCMAKE_INSTALL_PREFIX=${FAKE_INSTALL_PREFIX}" ) +set(GZ_PHYSICS_RESOURCE_DIR "${CMAKE_SOURCE_DIR}/resources") +add_library(gz-physics-test INTERFACE) +target_include_directories(gz-physics-test INTERFACE ${CMAKE_CURRENT_SOURCE_DIR}/include) +target_compile_definitions(gz-physics-test INTERFACE + "GZ_PHYSICS_RESOURCE_DIR=\"${GZ_PHYSICS_RESOURCE_DIR}\"" + "TESTING_PROJECT_SOURCE_DIR=\"${PROJECT_SOURCE_DIR}\"" +) +target_link_libraries(gz-physics-test INTERFACE + gz-plugin${GZ_PLUGIN_VER}::loader + gz-common${GZ_COMMON_VER}::gz-common${GZ_COMMON_VER} + gz-common${GZ_COMMON_VER}::testing +) + add_subdirectory(gtest_vendor) add_subdirectory(benchmark) add_subdirectory(common_test) diff --git a/test/benchmark/CMakeLists.txt b/test/benchmark/CMakeLists.txt index ab3d40766..c9e800fde 100644 --- a/test/benchmark/CMakeLists.txt +++ b/test/benchmark/CMakeLists.txt @@ -4,5 +4,4 @@ set(tests ExpectData.cc ) -gz_add_benchmarks(SOURCES ${tests} - INCLUDE_DIRS ${PROJECT_SOURCE_DIR}/test) +gz_add_benchmarks(SOURCES ${tests} LIB_DEPS gz-physics-test) diff --git a/test/benchmark/ExpectData.cc b/test/benchmark/ExpectData.cc index 1bd8243e8..08c30bc20 100644 --- a/test/benchmark/ExpectData.cc +++ b/test/benchmark/ExpectData.cc @@ -1,6 +1,6 @@ #include -#include "TestDataTypes.hh" +#include "test/TestDataTypes.hh" std::size_t gNumTests = 100000; diff --git a/test/common_test/CMakeLists.txt b/test/common_test/CMakeLists.txt index c76f0754d..1ec78d74e 100644 --- a/test/common_test/CMakeLists.txt +++ b/test/common_test/CMakeLists.txt @@ -44,7 +44,6 @@ function(configure_common_test PHYSICS_ENGINE_NAME test_name) endif() endfunction() -set(GZ_PHYSICS_RESOURCE_DIR "${CMAKE_SOURCE_DIR}/resources") foreach(test ${tests}) set(test_executable "${TEST_TYPE}_${test}") @@ -52,9 +51,7 @@ foreach(test ${tests}) target_link_libraries(${test_executable} PUBLIC - gz-plugin${GZ_PLUGIN_VER}::loader - gz-common${GZ_COMMON_VER}::gz-common${GZ_COMMON_VER} - gz-common${GZ_COMMON_VER}::testing + gz-physics-test ${PROJECT_LIBRARY_TARGET_NAME} ${PROJECT_LIBRARY_TARGET_NAME}-sdf ${PROJECT_LIBRARY_TARGET_NAME}-mesh @@ -62,17 +59,9 @@ foreach(test ${tests}) gtest_main ) - target_include_directories(${test_executable} - PUBLIC - ${PROJECT_SOURCE_DIR}/test) - - target_compile_definitions(${test_executable} PRIVATE - "GZ_PHYSICS_RESOURCE_DIR=\"${GZ_PHYSICS_RESOURCE_DIR}\"" - "TESTING_PROJECT_SOURCE_DIR=\"${PROJECT_SOURCE_DIR}\"" - ) + target_include_directories(${test_executable} PUBLIC ${CMAKE_CURRENT_SOURCE_DIR}) install(TARGETS ${test_executable} DESTINATION ${TEST_INSTALL_DIR}) - configure_common_test("bullet" ${test_executable}) configure_common_test("bullet-featherstone" ${test_executable}) configure_common_test("dartsim" ${test_executable}) diff --git a/test/common_test/added_mass.cc b/test/common_test/added_mass.cc index 506ec2d58..45b4f06b3 100644 --- a/test/common_test/added_mass.cc +++ b/test/common_test/added_mass.cc @@ -17,12 +17,12 @@ #include #include -#include #include -#include "TestLibLoader.hh" -#include "../Utils.hh" +#include "test/TestLibLoader.hh" +#include "test/Utils.hh" +#include "worlds/Worlds.hh" #include #include @@ -87,10 +87,8 @@ TEST_F(AddedMassFeaturesTest, Gravity) EXPECT_TRUE(engine->GetName().find(this->PhysicsEngineName(name)) != std::string::npos); - const auto worldPath = - gz::common::testing::TestFile("common_test", "worlds", "falling_added_mass.world"); sdf::Root root; - const sdf::Errors errors = root.Load(worldPath); + const sdf::Errors errors = root.Load(worlds::kFallingAddedMassWorld); EXPECT_TRUE(errors.empty()) << errors; const sdf::World *sdfWorld = root.WorldByIndex(0); EXPECT_NE(nullptr, sdfWorld); diff --git a/test/common_test/addexternalforcetorque.cc b/test/common_test/addexternalforcetorque.cc index 0ccf21ef3..a6863260e 100644 --- a/test/common_test/addexternalforcetorque.cc +++ b/test/common_test/addexternalforcetorque.cc @@ -24,8 +24,9 @@ #include #include -#include "TestLibLoader.hh" -#include "Utils.hh" +#include "test/TestLibLoader.hh" +#include "test/Utils.hh" +#include "worlds/Worlds.hh" #include #include @@ -45,8 +46,6 @@ #include #include -#include - template class LinkFeaturesTest: public testing::Test, public gz::physics::TestLibLoader @@ -110,10 +109,7 @@ TYPED_TEST(LinkFeaturesTest, JointSetCommand) ASSERT_NE(nullptr, engine); sdf::Root root; - - const auto worldPath = - gz::common::testing::TestFile("common_test", "worlds", "sphere.sdf"); - const sdf::Errors errors = root.Load(worldPath); + const sdf::Errors errors = root.Load(worlds::kSphereSdf); ASSERT_TRUE(errors.empty()) << errors.front(); const std::string modelName{"sphere"}; diff --git a/test/common_test/basic_test.cc b/test/common_test/basic_test.cc index a3b91d87b..96af1eeb5 100644 --- a/test/common_test/basic_test.cc +++ b/test/common_test/basic_test.cc @@ -19,7 +19,7 @@ #include #include -#include "TestLibLoader.hh" +#include "test/TestLibLoader.hh" #include #include diff --git a/test/common_test/collisions.cc b/test/common_test/collisions.cc index 48189718c..343255bf0 100644 --- a/test/common_test/collisions.cc +++ b/test/common_test/collisions.cc @@ -19,7 +19,7 @@ #include #include -#include "TestLibLoader.hh" +#include "test/TestLibLoader.hh" #include #include diff --git a/test/common_test/construct_empty_world.cc b/test/common_test/construct_empty_world.cc index a2974aaba..f454b9ee4 100644 --- a/test/common_test/construct_empty_world.cc +++ b/test/common_test/construct_empty_world.cc @@ -19,7 +19,7 @@ #include #include -#include "TestLibLoader.hh" +#include "test/TestLibLoader.hh" #include #include diff --git a/test/common_test/detachable_joint.cc b/test/common_test/detachable_joint.cc index 7fb25cf53..7d5321e1d 100644 --- a/test/common_test/detachable_joint.cc +++ b/test/common_test/detachable_joint.cc @@ -25,8 +25,9 @@ #include #include -#include "TestLibLoader.hh" -#include "../Utils.hh" +#include "test/TestLibLoader.hh" +#include "test/Utils.hh" +#include "worlds/Worlds.hh" #include "gz/physics/FrameSemantics.hh" #include @@ -110,10 +111,8 @@ TYPED_TEST(DetachableJointTest, CorrectAttachmentPoints) gz::physics::RequestEngine3d::From(plugin); ASSERT_NE(nullptr, engine); - const auto worldPath = - gz::common::testing::TestFile("common_test", "worlds", "detachable_joint.world"); sdf::Root root; - const sdf::Errors errors = root.Load(worldPath); + const sdf::Errors errors = root.Load(worlds::kDetachableJointWorld); ASSERT_TRUE(errors.empty()) << errors.front(); auto world = engine->ConstructWorld(*root.WorldByIndex(0)); diff --git a/test/common_test/free_joint_features.cc b/test/common_test/free_joint_features.cc index 3f4c99ad0..99f819c2a 100644 --- a/test/common_test/free_joint_features.cc +++ b/test/common_test/free_joint_features.cc @@ -18,7 +18,8 @@ #include -#include "TestLibLoader.hh" +#include "worlds/Worlds.hh" +#include "test/TestLibLoader.hh" #include #include @@ -37,8 +38,6 @@ #include "gz/physics/sdf/ConstructNestedModel.hh" #include "gz/physics/sdf/ConstructWorld.hh" -#include - struct TestFeatureList : gz::physics::FeatureList< gz::physics::GetEngineInfo, gz::physics::sdf::ConstructSdfWorld, @@ -113,9 +112,7 @@ TEST_F(FreeGroupFeaturesTest, NestedFreeGroup) ASSERT_NE(nullptr, engine); sdf::Root root; - const auto worldPath = - gz::common::testing::TestFile("common_test", "worlds", "world_with_nested_model.sdf"); - const sdf::Errors &errors = root.Load(worldPath); + const sdf::Errors &errors = root.Load(worlds::kWorldWithNestedModelSdf); EXPECT_EQ(0u, errors.size()) << errors; EXPECT_EQ(1u, root.WorldCount()); @@ -166,9 +163,7 @@ TEST_F(FreeGroupFeaturesTest, NestedFreeGroupSetWorldPose) ASSERT_NE(nullptr, engine); sdf::Root root; - const auto worldPath = - gz::common::testing::TestFile("common_test", "worlds", "world_with_nested_model.sdf"); - const sdf::Errors &errors = root.Load(worldPath); + const sdf::Errors &errors = root.Load(worlds::kWorldWithNestedModelSdf); EXPECT_EQ(0u, errors.size()) << errors; EXPECT_EQ(1u, root.WorldCount()); diff --git a/test/common_test/joint_features.cc b/test/common_test/joint_features.cc index 2279c30d7..c784ff830 100644 --- a/test/common_test/joint_features.cc +++ b/test/common_test/joint_features.cc @@ -24,8 +24,9 @@ #include #include -#include "TestLibLoader.hh" -#include "../Utils.hh" +#include "worlds/Worlds.hh" +#include "test/TestLibLoader.hh" +#include "test/Utils.hh" #include "gz/physics/FrameSemantics.hh" #include @@ -44,8 +45,6 @@ #include -#include - template class JointFeaturesTest: public testing::Test, public gz::physics::TestLibLoader @@ -116,10 +115,8 @@ TYPED_TEST(JointFeaturesTest, JointSetCommand) auto engine = gz::physics::RequestEngine3d::From(plugin); ASSERT_NE(nullptr, engine); - const auto worldPath = - gz::common::testing::TestFile("common_test", "worlds", "test.world"); sdf::Root root; - const sdf::Errors errors = root.Load(worldPath); + const sdf::Errors errors = root.Load(worlds::kTestWorld); ASSERT_TRUE(errors.empty()) << errors.front(); const std::string modelName{"double_pendulum_with_base"}; @@ -228,10 +225,8 @@ TYPED_TEST(JointFeaturesPositionLimitsTest, JointSetPositionLimitsWithForceContr auto engine = gz::physics::RequestEngine3d::From(plugin); ASSERT_NE(nullptr, engine); - const auto worldPath = - gz::common::testing::TestFile("common_test", "worlds", "test.world"); sdf::Root root; - const sdf::Errors errors = root.Load(worldPath); + const sdf::Errors errors = root.Load(worlds::kTestWorld); ASSERT_TRUE(errors.empty()) << errors.front(); auto world = engine->ConstructWorld(*root.WorldByIndex(0)); @@ -336,10 +331,8 @@ TYPED_TEST(JointFeaturesPositionLimitsForceControlTest, JointSetVelocityLimitsWi gz::physics::RequestEngine3d::From(plugin); ASSERT_NE(nullptr, engine); - const auto worldPath = - gz::common::testing::TestFile("common_test", "worlds", "test.world"); sdf::Root root; - const sdf::Errors errors = root.Load(worldPath); + const sdf::Errors errors = root.Load(worlds::kTestWorld); ASSERT_TRUE(errors.empty()) << errors.front(); auto world = engine->ConstructWorld(*root.WorldByIndex(0)); @@ -425,10 +418,8 @@ TYPED_TEST(JointFeaturesPositionLimitsForceControlTest, JointSetEffortLimitsWith gz::physics::RequestEngine3d::From(plugin); ASSERT_NE(nullptr, engine); - const auto worldPath = - gz::common::testing::TestFile("common_test", "worlds", "test.world"); sdf::Root root; - const sdf::Errors errors = root.Load(worldPath); + const sdf::Errors errors = root.Load(worlds::kTestWorld); ASSERT_TRUE(errors.empty()) << errors.front(); auto world = engine->ConstructWorld(*root.WorldByIndex(0)); @@ -504,10 +495,8 @@ TYPED_TEST(JointFeaturesPositionLimitsForceControlTest, JointSetCombinedLimitsWi gz::physics::RequestEngine3d::From(plugin); ASSERT_NE(nullptr, engine); - const auto worldPath = - gz::common::testing::TestFile("common_test", "worlds", "test.world"); sdf::Root root; - const sdf::Errors errors = root.Load(worldPath); + const sdf::Errors errors = root.Load(worlds::kTestWorld); ASSERT_TRUE(errors.empty()) << errors.front(); auto world = engine->ConstructWorld(*root.WorldByIndex(0)); @@ -614,10 +603,8 @@ TYPED_TEST(JointFeaturesPositionLimitsForceControlTest, DISABLED_JointSetPositio gz::physics::RequestEngine3d::From(plugin); ASSERT_NE(nullptr, engine); - const auto worldPath = - gz::common::testing::TestFile("common_test", "worlds", "test.world"); sdf::Root root; - const sdf::Errors errors = root.Load(worldPath); + const sdf::Errors errors = root.Load(worlds::kTestWorld); ASSERT_TRUE(errors.empty()) << errors.front(); const std::string modelName{"simple_joint_test"}; @@ -668,10 +655,8 @@ TYPED_TEST(JointFeaturesPositionLimitsForceControlTest, JointSetVelocityLimitsWi gz::physics::RequestEngine3d::From(plugin); ASSERT_NE(nullptr, engine); - const auto worldPath = - gz::common::testing::TestFile("common_test", "worlds", "test.world"); sdf::Root root; - const sdf::Errors errors = root.Load(worldPath); + const sdf::Errors errors = root.Load(worlds::kTestWorld); ASSERT_TRUE(errors.empty()) << errors.front(); auto world = engine->ConstructWorld(*root.WorldByIndex(0)); @@ -741,10 +726,8 @@ TYPED_TEST(JointFeaturesPositionLimitsForceControlTest, JointSetEffortLimitsWith gz::physics::RequestEngine3d::From(plugin); ASSERT_NE(nullptr, engine); - const auto worldPath = - gz::common::testing::TestFile("common_test", "worlds", "test.world"); sdf::Root root; - const sdf::Errors errors = root.Load(worldPath); + const sdf::Errors errors = root.Load(worlds::kTestWorld); ASSERT_TRUE(errors.empty()) << errors.front(); auto world = engine->ConstructWorld(*root.WorldByIndex(0)); @@ -803,10 +786,8 @@ TYPED_TEST(JointFeaturesPositionLimitsForceControlTest, JointSetCombinedLimitsWi gz::physics::RequestEngine3d::From(plugin); ASSERT_NE(nullptr, engine); - const auto worldPath = - gz::common::testing::TestFile("common_test", "worlds", "test.world"); sdf::Root root; - const sdf::Errors errors = root.Load(worldPath); + const sdf::Errors errors = root.Load(worlds::kTestWorld); ASSERT_TRUE(errors.empty()) << errors.front(); auto world = engine->ConstructWorld(*root.WorldByIndex(0)); @@ -880,10 +861,8 @@ TYPED_TEST(JointFeaturesDetachTest, JointDetach) auto engine = gz::physics::RequestEngine3d::From(plugin); ASSERT_NE(nullptr, engine); - const auto worldPath = - gz::common::testing::TestFile("common_test", "worlds", "test.world"); sdf::Root root; - const sdf::Errors errors = root.Load(worldPath); + const sdf::Errors errors = root.Load(worlds::kTestWorld); ASSERT_TRUE(errors.empty()) << errors.front(); const std::string modelName{"double_pendulum_with_base"}; @@ -1043,10 +1022,8 @@ TYPED_TEST(JointFeaturesAttachDetachTest, JointAttachDetach) auto engine = gz::physics::RequestEngine3d::From(plugin); ASSERT_NE(nullptr, engine); - const auto worldPath = - gz::common::testing::TestFile("common_test", "worlds", "joint_across_models.sdf"); sdf::Root root; - const sdf::Errors errors = root.Load(worldPath); + const sdf::Errors errors = root.Load(worlds::kJointAcrossModelsSdf); ASSERT_TRUE(errors.empty()) << errors.front(); auto world = engine->ConstructWorld(*root.WorldByIndex(0)); @@ -1189,10 +1166,8 @@ TYPED_TEST(JointFeaturesAttachDetachTest, JointAttachMultiple) auto engine = gz::physics::RequestEngine3d::From(plugin); ASSERT_NE(nullptr, engine); - const auto worldPath = - gz::common::testing::TestFile("common_test", "worlds", "joint_constraint.sdf"); sdf::Root root; - const sdf::Errors errors = root.Load(worldPath); + const sdf::Errors errors = root.Load(worlds::kJointConstraintSdf); ASSERT_TRUE(errors.empty()) << errors.front(); auto world = engine->ConstructWorld(*root.WorldByIndex(0)); @@ -1340,10 +1315,8 @@ TYPED_TEST(JointFeaturesAttachDetachTest, LinkCountsInJointAttachDetach) auto engine = gz::physics::RequestEngine3d::From(plugin); ASSERT_NE(nullptr, engine); - const auto worldPath = - gz::common::testing::TestFile("common_test", "worlds", "joint_across_models.sdf"); sdf::Root root; - const sdf::Errors errors = root.Load(worldPath); + const sdf::Errors errors = root.Load(worlds::kJointAcrossModelsSdf); ASSERT_TRUE(errors.empty()) << errors.front(); auto world = engine->ConstructWorld(*root.WorldByIndex(0)); @@ -1439,10 +1412,8 @@ TYPED_TEST(JointFeaturesAttachDetachTest, JointAttachDetachSpawnedModel) auto engine = gz::physics::RequestEngine3d::From(plugin); ASSERT_NE(nullptr, engine); - const auto worldPath = - gz::common::testing::TestFile("common_test", "worlds", "ground.sdf"); sdf::Root root; - const sdf::Errors errors = root.Load(worldPath); + const sdf::Errors errors = root.Load(worlds::kGroundSdf); ASSERT_TRUE(errors.empty()) << errors.front(); world = engine->ConstructWorld(*root.WorldByIndex(0)); @@ -1540,8 +1511,7 @@ class WorldModelTest : public JointFeaturesTest gz::physics::RequestEngine3d::From(plugin); sdf::Root root; - const sdf::Errors errors = root.Load( - gz::common::joinPaths(TEST_WORLD_DIR, "world_joint_test.sdf")); + const sdf::Errors errors = root.Load(worlds::kWorldJointTestSdf); EXPECT_TRUE(errors.empty()) << errors; if (errors.empty()) { diff --git a/test/common_test/joint_transmitted_wrench_features.cc b/test/common_test/joint_transmitted_wrench_features.cc index fd980923f..57fd65f05 100644 --- a/test/common_test/joint_transmitted_wrench_features.cc +++ b/test/common_test/joint_transmitted_wrench_features.cc @@ -26,8 +26,9 @@ #include #include -#include "TestLibLoader.hh" -#include "../Utils.hh" +#include "worlds/Worlds.hh" +#include "test/TestLibLoader.hh" +#include "test/Utils.hh" #include "gz/physics/FrameSemantics.hh" #include diff --git a/test/common_test/kinematic_features.cc b/test/common_test/kinematic_features.cc index 212c34786..e70b45b81 100644 --- a/test/common_test/kinematic_features.cc +++ b/test/common_test/kinematic_features.cc @@ -19,8 +19,9 @@ #include #include -#include "TestLibLoader.hh" -#include "../Utils.hh" +#include "worlds/Worlds.hh" +#include "test/TestLibLoader.hh" +#include "test/Utils.hh" #include #include diff --git a/test/common_test/link_features.cc b/test/common_test/link_features.cc index 4dd563441..859309ff1 100644 --- a/test/common_test/link_features.cc +++ b/test/common_test/link_features.cc @@ -24,8 +24,9 @@ #include #include -#include "TestLibLoader.hh" -#include "../Utils.hh" +#include "worlds/Worlds.hh" +#include "test/TestLibLoader.hh" +#include "test/Utils.hh" #include #include @@ -42,8 +43,6 @@ #include #include -#include - template class LinkFeaturesTest: public testing::Test, public gz::physics::TestLibLoader @@ -106,10 +105,8 @@ TYPED_TEST(LinkFeaturesTest, JointSetCommand) auto engine = gz::physics::RequestEngine3d::From(plugin); ASSERT_NE(nullptr, engine); - const auto worldPath = - gz::common::testing::TestFile("common_test", "worlds", "empty.sdf"); sdf::Root root; - const sdf::Errors errors = root.Load(worldPath); + const sdf::Errors errors = root.Load(worlds::kEmptySdf); ASSERT_TRUE(errors.empty()) << errors.front(); const std::string modelName{"double_pendulum_with_base"}; @@ -306,10 +303,8 @@ TYPED_TEST(LinkFeaturesTest, AxisAlignedBoundingBox) auto engine = gz::physics::RequestEngine3d::From(plugin); ASSERT_NE(nullptr, engine); - const auto worldPath = - gz::common::testing::TestFile("common_test", "worlds", "test.world"); sdf::Root root; - const sdf::Errors errors = root.Load(worldPath); + const sdf::Errors errors = root.Load(worlds::kTestWorld); ASSERT_TRUE(errors.empty()) << errors.front(); const std::string modelName{"double_pendulum_with_base"}; @@ -359,10 +354,8 @@ TYPED_TEST(LinkFeaturesTest, ModelAxisAlignedBoundingBox) auto engine = gz::physics::RequestEngine3d::From(plugin); ASSERT_NE(nullptr, engine); - const auto worldPath = - gz::common::testing::TestFile("common_test", "worlds", "contact.sdf"); sdf::Root root; - const sdf::Errors errors = root.Load(worldPath); + const sdf::Errors errors = root.Load(worlds::kContactSdf); ASSERT_TRUE(errors.empty()) << errors.front(); const std::string modelName{"double_pendulum_with_base"}; diff --git a/test/common_test/shape_features.cc b/test/common_test/shape_features.cc index 92fb89bfc..93bb45a09 100644 --- a/test/common_test/shape_features.cc +++ b/test/common_test/shape_features.cc @@ -19,8 +19,9 @@ #include #include -#include "TestLibLoader.hh" -#include "../Utils.hh" +#include "test/TestLibLoader.hh" +#include "test/Utils.hh" +#include "worlds/Worlds.hh" // Features #include @@ -104,10 +105,8 @@ TYPED_TEST(ShapeFeaturesTest, PrimarySlipCompliance) auto engine = gz::physics::RequestEngine3d::From(plugin); ASSERT_NE(nullptr, engine); - const auto worldPath = - gz::common::testing::TestFile("common_test", "worlds", "slip_compliance.sdf"); sdf::Root root; - const sdf::Errors errors = root.Load(worldPath); + const sdf::Errors errors = root.Load(worlds::kSlipComplianceSdf); ASSERT_TRUE(errors.empty()) << errors.front(); const std::string modelName{"box"}; @@ -178,10 +177,8 @@ TYPED_TEST(ShapeFeaturesTest, SecondarySlipCompliance) auto engine = gz::physics::RequestEngine3d::From(plugin); ASSERT_NE(nullptr, engine); - const auto worldPath = - gz::common::testing::TestFile("common_test", "worlds", "slip_compliance.sdf"); sdf::Root root; - const sdf::Errors errors = root.Load(worldPath); + const sdf::Errors errors = root.Load(worlds::kSlipComplianceSdf); ASSERT_TRUE(errors.empty()) << errors.front(); const std::string modelName{"box"}; diff --git a/test/common_test/simulation_features.cc b/test/common_test/simulation_features.cc index b64c567f9..fad240765 100644 --- a/test/common_test/simulation_features.cc +++ b/test/common_test/simulation_features.cc @@ -25,8 +25,9 @@ #include -#include "TestLibLoader.hh" -#include "../Utils.hh" +#include "test/TestLibLoader.hh" +#include "test/Utils.hh" +#include "worlds/Worlds.hh" #include #include @@ -51,8 +52,6 @@ #include -#include - // The features that an engine must have to be loaded by this loader. struct Features : gz::physics::FeatureList< gz::physics::ConstructEmptyWorldFeature, @@ -202,12 +201,6 @@ using SimulationFeaturesContactsTestTypes = TYPED_TEST_SUITE(SimulationFeaturesContactsTest, SimulationFeaturesContactsTestTypes); -///////////////////////////////////////////////// -std::string CommonTestFile(const std::string &_worldName) -{ - return gz::common::testing::TestFile("common_test", "worlds", _worldName); -} - ///////////////////////////////////////////////// TYPED_TEST(SimulationFeaturesContactsTest, Contacts) { @@ -216,7 +209,7 @@ TYPED_TEST(SimulationFeaturesContactsTest, Contacts) auto world = LoadPluginAndWorld( this->loader, name, - CommonTestFile("shapes.world")); + worlds::kShapesWorld); auto checkedOutput = StepWorld(world, true, 1).first; EXPECT_TRUE(checkedOutput); @@ -253,7 +246,7 @@ TYPED_TEST(SimulationFeaturesStepTest, StepWorld) auto world = LoadPluginAndWorld( this->loader, name, - gz::common::testing::TestFile("common_test", "worlds", "shapes.world")); + worlds::kShapesWorld); auto checkedOutput = StepWorld(world, true, 1000).first; EXPECT_TRUE(checkedOutput); } @@ -288,7 +281,7 @@ TYPED_TEST(SimulationFeaturesFallingTest, Falling) #endif auto world = LoadPluginAndWorld( this->loader, name, - gz::common::testing::TestFile("common_test", "worlds", "falling.world")); + worlds::kFallingWorld); auto [checkedOutput, output] = StepWorld(world, true, 1000); @@ -351,7 +344,7 @@ TYPED_TEST(SimulationFeaturesShapeFeaturesTest, ShapeFeatures) #endif auto world = LoadPluginAndWorld( this->loader, name, - gz::common::testing::TestFile("common_test", "worlds", "shapes.world")); + worlds::kShapesWorld); std::cerr << "world model count " << world->GetModelCount() << '\n'; // test ShapeFeatures auto sphere = world->GetModel("sphere"); @@ -530,7 +523,7 @@ TYPED_TEST(SimulationFeaturesTestFreeGroup, FreeGroup) auto world = LoadPluginAndWorld( this->loader, name, - gz::common::testing::TestFile("common_test", "worlds", "shapes.world")); + worlds::kShapesWorld); // model free group test auto model = world->GetModel("sphere"); @@ -618,7 +611,7 @@ TYPED_TEST(SimulationFeaturesTestBasic, ShapeBoundingBox) auto world = LoadPluginAndWorld( this->loader, name, - gz::common::testing::TestFile("common_test", "worlds", "falling.world")); + worlds::kFallingWorld); auto sphere = world->GetModel("sphere"); auto sphereCollision = sphere->GetLink(0)->GetShape(0); auto ground = world->GetModel("box"); @@ -667,7 +660,7 @@ TYPED_TEST(SimulationFeaturesTestBasic, CollideBitmasks) auto world = LoadPluginAndWorld( this->loader, name, - gz::common::testing::TestFile("common_test", "worlds", "shapes_bitmask.sdf")); + worlds::kShapesBitmaskWorld); auto baseBox = world->GetModel("box_base"); auto filteredBox = world->GetModel("box_filtered"); @@ -712,7 +705,7 @@ TYPED_TEST(SimulationFeaturesTestBasic, RetrieveContacts) LoadPluginAndWorld( this->loader, name, - gz::common::testing::TestFile("common_test", "worlds", "shapes.world")); + worlds::kShapesWorld); auto sphere = world->GetModel("sphere"); auto sphereFreeGroup = sphere->FindFreeGroup(); @@ -924,7 +917,7 @@ TYPED_TEST(SimulationFeaturesTestFeaturesContactPropertiesCallback, ContactPrope LoadPluginAndWorld( this->loader, name, - gz::common::testing::TestFile("common_test", "worlds", "contact.sdf")); + worlds::kContactSdf); auto sphere = world->GetModel("sphere"); auto groundPlane = world->GetModel("ground_plane"); @@ -1154,7 +1147,7 @@ TYPED_TEST(SimulationFeaturesTestBasic, MultipleCollisions) auto world = LoadPluginAndWorld( this->loader, name, - gz::common::joinPaths(TEST_WORLD_DIR, "multiple_collisions.sdf")); + worlds::kMultipleCollisionsSdf); // model free group test auto model = world->GetModel("box"); diff --git a/test/common_test/world_features.cc b/test/common_test/world_features.cc index 21f84d964..b5b04dcb7 100644 --- a/test/common_test/world_features.cc +++ b/test/common_test/world_features.cc @@ -19,8 +19,9 @@ #include #include -#include "TestLibLoader.hh" -#include "../Utils.hh" +#include "test/TestLibLoader.hh" +#include "test/Utils.hh" +#include "worlds/Worlds.hh" #include #include @@ -39,8 +40,6 @@ #include -#include - using AssertVectorApprox = gz::physics::test::AssertVectorApprox; template @@ -81,12 +80,6 @@ struct GravityFeatures : gz::physics::FeatureList< using WorldFeaturesTestGravity = WorldFeaturesTest; -///////////////////////////////////////////////// -std::string CommonTestFile(const std::string &_worldName) -{ - return gz::common::testing::TestFile("common_test", "worlds", _worldName); -} - ///////////////////////////////////////////////// TEST_F(WorldFeaturesTestGravity, GravityFeatures) { @@ -100,10 +93,8 @@ TEST_F(WorldFeaturesTestGravity, GravityFeatures) EXPECT_TRUE(engine->GetName().find(this->PhysicsEngineName(name)) != std::string::npos); - const auto worldPath = - gz::common::testing::TestFile("common_test", "worlds", "falling.world"); sdf::Root root; - const sdf::Errors errors = root.Load(worldPath); + const sdf::Errors errors = root.Load(worlds::kFallingWorld); EXPECT_TRUE(errors.empty()) << errors; const sdf::World *sdfWorld = root.WorldByIndex(0); EXPECT_NE(nullptr, sdfWorld); @@ -214,8 +205,7 @@ TEST_F(WorldFeaturesTestConstructModel, ConstructModelUnsortedLinks) std::string::npos); sdf::Root root; - const sdf::Errors errors = root.Load( - CommonTestFile("world_unsorted_links.sdf")); + const sdf::Errors errors = root.Load(worlds::kWorldUnsortedLinksSdf); EXPECT_TRUE(errors.empty()) << errors; const sdf::World *sdfWorld = root.WorldByIndex(0); @@ -254,7 +244,7 @@ class WorldModelTest : public WorldFeaturesTest gz::physics::RequestEngine3d::From(plugin); sdf::Root root; - const sdf::Errors errors = root.Load(CommonTestFile("world_joint_test.sdf")); + const sdf::Errors errors = root.Load(worlds::kWorldJointTestSdf); EXPECT_TRUE(errors.empty()) << errors; if (errors.empty()) { diff --git a/test/common_test/worlds/Worlds.hh b/test/common_test/worlds/Worlds.hh new file mode 100644 index 000000000..6325d4933 --- /dev/null +++ b/test/common_test/worlds/Worlds.hh @@ -0,0 +1,54 @@ +/* + * Copyright (C) 2024 Open Source Robotics Foundation + * + * 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. + * + */ + +#ifndef COMMON_TEST_WORLDS_WORLDS_HH_ +#define COMMON_TEST_WORLDS_WORLDS_HH_ + +#include + +#include + +inline std::string CommonTestWorld(const std::string &_world) +{ + return gz::common::testing::TestFile("common_test", "worlds", _world); +} + +namespace worlds +{ +const auto kContactSdf = CommonTestWorld("contact.sdf"); +const auto kDetachableJointWorld = CommonTestWorld("detachable_joint.world"); +const auto kEmptySdf = CommonTestWorld("empty.sdf"); +const auto kFallingWorld = CommonTestWorld("falling.world"); +const auto kFallingAddedMassWorld = CommonTestWorld("falling_added_mass.world"); +const auto kGroundSdf = CommonTestWorld("ground.sdf"); +const auto kJointAcrossModelsSdf = CommonTestWorld("joint_across_models.sdf"); +const auto kJointConstraintSdf = CommonTestWorld("joint_constraint.sdf"); +const auto kMultipleCollisionsSdf = CommonTestWorld("multiple_collisions.sdf"); +const auto kPendulumJointWrenchSdf = + CommonTestWorld("pendulum_joint_wrench.sdf"); +const auto kShapesWorld = CommonTestWorld("shapes.world"); +const auto kShapesBitmaskWorld = CommonTestWorld("shapes_bitmask.sdf"); +const auto kSlipComplianceSdf = CommonTestWorld("slip_compliance.sdf"); +const auto kSphereSdf = CommonTestWorld("sphere.sdf"); +const auto kStringPendulumSdf = CommonTestWorld("string_pendulum.sdf"); +const auto kTestWorld = CommonTestWorld("test.world"); +const auto kWorldJointTestSdf = CommonTestWorld("world_joint_test.sdf"); +const auto kWorldUnsortedLinksSdf = CommonTestWorld("world_unsorted_links.sdf"); +const auto kWorldWithNestedModelSdf = + CommonTestWorld("world_with_nested_model.sdf"); +} // namespace worlds +#endif // COMMON_TEST_WORLDS_WORLDS_HH_ diff --git a/test/include/test/Utils.hh b/test/include/test/Utils.hh index e38f23648..81d865ef2 100644 --- a/test/include/test/Utils.hh +++ b/test/include/test/Utils.hh @@ -23,6 +23,9 @@ #include #include #include +#include + +#include #include @@ -40,10 +43,10 @@ inline void PrimeTheLoader(gz::plugin::Loader &_loader) namespace gz::physics::test { ///////////////////////////////////////////////// -class UnimplementedFeature : public virtual physics::Feature +class UnimplementedFeature : public virtual gz::physics::Feature { public: template - class Implementation : public virtual Feature::Implementation + class Implementation : public virtual gz::physics::Feature::Implementation { public: virtual void someUnimplementedVirtualFunction() = 0; diff --git a/test/integration/CMakeLists.txt b/test/integration/CMakeLists.txt index 0b531c990..8c0b32183 100644 --- a/test/integration/CMakeLists.txt +++ b/test/integration/CMakeLists.txt @@ -11,14 +11,10 @@ gz_build_tests( SOURCES ${tests} LIB_DEPS Eigen3::Eigen - gz-plugin${GZ_PLUGIN_VER}::loader - INCLUDE_DIRS - ${PROJECT_SOURCE_DIR}/src - ${PROJECT_SOURCE_DIR}/test + gz-physics-test TEST_LIST list ENVIRONMENT GZ_PHYSICS_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX} - ${PROJECT_SOURCE_DIR}/test TEST_LIST list) if (BUILD_TESTING) diff --git a/test/integration/CanReadWrite.cc b/test/integration/CanReadWrite.cc index 168bc6f6e..1385c08e6 100644 --- a/test/integration/CanReadWrite.cc +++ b/test/integration/CanReadWrite.cc @@ -23,7 +23,7 @@ #include "gz/physics/CanReadData.hh" #include "gz/physics/CanWriteData.hh" -#include "TestDataTypes.hh" +#include "test/TestDataTypes.hh" using gz::physics::CanReadRequiredData; using gz::physics::CanReadExpectedData; diff --git a/test/integration/DoublePendulum.cc b/test/integration/DoublePendulum.cc index 329d1e5e2..482e2e137 100644 --- a/test/integration/DoublePendulum.cc +++ b/test/integration/DoublePendulum.cc @@ -26,7 +26,7 @@ #include #include -#include "../MockDoublePendulum.hh" +#include "mock/MockDoublePendulum.hh" using namespace gz::physics; diff --git a/test/integration/FeatureSystem.cc b/test/integration/FeatureSystem.cc index 48fd3b453..46ee7a74f 100644 --- a/test/integration/FeatureSystem.cc +++ b/test/integration/FeatureSystem.cc @@ -20,7 +20,7 @@ #include #include -#include "../MockFeatures.hh" +#include "mock/MockFeatures.hh" using namespace gz::physics; diff --git a/test/integration/FrameSemantics.hh b/test/integration/FrameSemantics.hh index 57de63556..093776189 100644 --- a/test/integration/FrameSemantics.hh +++ b/test/integration/FrameSemantics.hh @@ -27,8 +27,8 @@ #include #include -#include "../Utils.hh" -#include "../MockFrameSemantics.hh" +#include "test/Utils.hh" +#include "mock/MockFrameSemantics.hh" using gz::physics::FrameData; using gz::physics::FrameID; diff --git a/test/integration/JointTypes.hh b/test/integration/JointTypes.hh index d658604c9..dc4f730f1 100644 --- a/test/integration/JointTypes.hh +++ b/test/integration/JointTypes.hh @@ -29,8 +29,8 @@ #include #include -#include "../MockJoints.hh" -#include "../Utils.hh" +#include "mock/MockJoints.hh" +#include "test/Utils.hh" using namespace gz::physics; using namespace gz::physics::test; diff --git a/test/integration/RequestFeatures.cc b/test/integration/RequestFeatures.cc index 9272a04b1..81f70c5fc 100644 --- a/test/integration/RequestFeatures.cc +++ b/test/integration/RequestFeatures.cc @@ -29,8 +29,8 @@ #include -#include "TestUtilities.hh" -#include "MockFeatures.hh" +#include "test/Utils.hh" +#include "mock/MockFeatures.hh" TEST(RequestFeatures_TEST, Casting) { @@ -48,7 +48,7 @@ TEST(RequestFeatures_TEST, Casting) mock::MockCenterOfMass>; using UnavailableFeatures = - gz::physics::FeatureList; + gz::physics::FeatureList; // Get a list of all plugins who satisfy the features that are needed for // testing diff --git a/test/performance/CMakeLists.txt b/test/performance/CMakeLists.txt index ae3a079e6..dcb1ae5f7 100644 --- a/test/performance/CMakeLists.txt +++ b/test/performance/CMakeLists.txt @@ -10,11 +10,8 @@ endif() gz_build_tests( TYPE PERFORMANCE SOURCES ${tests} - INCLUDE_DIRS - ${PROJECT_SOURCE_DIR}/src - ${PROJECT_SOURCE_DIR}/test ENVIRONMENT GZ_PHYSICS_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX} - INCLUDE_DIRS - ${PROJECT_SOURCE_DIR}/test + LIB_DEPS + gz-physics-test ) diff --git a/test/performance/ExpectData.cc b/test/performance/ExpectData.cc index 7524ef35a..41ff92eca 100644 --- a/test/performance/ExpectData.cc +++ b/test/performance/ExpectData.cc @@ -21,7 +21,7 @@ #include #include -#include "TestDataTypes.hh" +#include "test/TestDataTypes.hh" std::size_t gNumTests = 100000; diff --git a/tpe/plugin/CMakeLists.txt b/tpe/plugin/CMakeLists.txt index 4b891031f..76aaae276 100644 --- a/tpe/plugin/CMakeLists.txt +++ b/tpe/plugin/CMakeLists.txt @@ -55,6 +55,7 @@ gz_build_tests( SOURCES ${test_sources} LIB_DEPS ${features} + gz-physics-test gz-plugin${GZ_PLUGIN_VER}::loader gz-common${GZ_COMMON_VER}::gz-common${GZ_COMMON_VER} gz-common${GZ_COMMON_VER}::testing