Skip to content

Commit

Permalink
Remaining test refactor
Browse files Browse the repository at this point in the history
Signed-off-by: Michael Carroll <[email protected]>
  • Loading branch information
mjcarroll committed Jan 8, 2024
1 parent c46d3f5 commit ad7d7a4
Show file tree
Hide file tree
Showing 14 changed files with 111 additions and 48 deletions.
10 changes: 1 addition & 9 deletions dartsim/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -87,6 +87,7 @@ gz_build_tests(
gz-plugin${GZ_PLUGIN_VER}::loader
gz-common${GZ_COMMON_VER}::gz-common${GZ_COMMON_VER}
gz-common${GZ_COMMON_VER}::geospatial
gz-common${GZ_COMMON_VER}::testing
${PROJECT_LIBRARY_TARGET_NAME}-sdf
${PROJECT_LIBRARY_TARGET_NAME}-heightmap
${PROJECT_LIBRARY_TARGET_NAME}-mesh
Expand All @@ -95,10 +96,8 @@ gz_build_tests(
GZ_PHYSICS_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX})

foreach(test ${tests})

target_compile_definitions(${test} PRIVATE
"dartsim_plugin_LIB=\"$<TARGET_FILE:${dartsim_plugin}>\""
"TEST_WORLD_DIR=\"${CMAKE_CURRENT_SOURCE_DIR}/worlds/\""
"GZ_PHYSICS_RESOURCE_DIR=\"${GZ_PHYSICS_RESOURCE_DIR}\"")

if (DART_HAS_CONTACT_SURFACE_HEADER)
Expand All @@ -108,10 +107,3 @@ foreach(test ${tests})
# Helps when we want to build a single test after making changes to dartsim_plugin
add_dependencies(${test} ${dartsim_plugin})
endforeach()

foreach(test UNIT_FindFeatures_TEST UNIT_RequestFeatures_TEST)
if(TARGET ${test})
target_compile_definitions(${test} PRIVATE
"dartsim_plugin_LIB=\"$<TARGET_FILE:${dartsim_plugin}>\"")
endif()
endforeach()
6 changes: 5 additions & 1 deletion dartsim/src/AddedMassFeatures_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,8 @@
#include <dart/dynamics/BodyNode.hpp>

#include <gz/common/Console.hh>
#include <gz/common/testing/TestPaths.hh>

#include <gz/math/eigen3.hh>
#include <gz/plugin/Loader.hh>

Expand Down Expand Up @@ -121,7 +123,9 @@ TEST(AddedMassFeatures, AddedMass)
0, 0, 0, 0, 1, 0,
0, 0, 0, 0, 0, 1;

auto world = LoadWorld(TEST_WORLD_DIR"/added_mass.sdf");
const auto worldPath =
gz::common::testing::SourceFile("dartsim", "worlds", "added_mass.sdf");
const auto world = LoadWorld(worldPath);
ASSERT_NE(nullptr, world);

auto dartWorld = world->GetDartsimWorld();
Expand Down
65 changes: 48 additions & 17 deletions dartsim/src/SDFFeatures_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@
*
*/

#include <tuple>
#include <type_traits>

#include <dart/dynamics/BodyNode.hpp>
Expand All @@ -26,7 +27,7 @@

#include <gtest/gtest.h>

#include <tuple>
#include <gz/common/testing/TestPaths.hh>

#include <gz/plugin/Loader.hh>

Expand Down Expand Up @@ -313,7 +314,9 @@ INSTANTIATE_TEST_SUITE_P(LoadWorld, SDFFeatures_TEST,
// Test that the dartsim plugin loaded all the relevant information correctly.
TEST_P(SDFFeatures_TEST, CheckDartsimData)
{
WorldPtr world = this->LoadWorld(TEST_WORLD_DIR"/test.world");
const auto worldPath =
gz::common::testing::SourceFile("dartsim", "worlds", "test.world");
WorldPtr world = this->LoadWorld(worldPath);
ASSERT_NE(nullptr, world);

dart::simulation::WorldPtr dartWorld = world->GetDartsimWorld();
Expand Down Expand Up @@ -421,7 +424,9 @@ TEST_P(SDFFeatures_TEST, CheckDartsimData)
// Test that joint limits are working by running the simulation
TEST_P(SDFFeatures_TEST, CheckJointLimitEnforcement)
{
WorldPtr world = this->LoadWorld(TEST_WORLD_DIR"/test.world");
const auto worldPath =
gz::common::testing::SourceFile("dartsim", "worlds", "test.world");
WorldPtr world = this->LoadWorld(worldPath);
ASSERT_NE(nullptr, world);

dart::simulation::WorldPtr dartWorld = world->GetDartsimWorld();
Expand Down Expand Up @@ -580,8 +585,10 @@ TEST_P(SDFFeatures_TEST, WorldIsParentOrChild)
//
TEST_P(SDFFeatures_TEST, WorldWithNestedModel)
{
WorldPtr world =
this->LoadWorld(TEST_WORLD_DIR "/world_with_nested_model.sdf");
const auto worldPath =
gz::common::testing::SourceFile(
"dartsim", "worlds", "world_with_nested_model.sdf");
WorldPtr world = this->LoadWorld(worldPath);
ASSERT_NE(nullptr, world);
EXPECT_EQ(2u, world->GetModelCount());

Expand Down Expand Up @@ -645,8 +652,10 @@ TEST_P(SDFFeatures_TEST, WorldWithNestedModel)
/////////////////////////////////////////////////
TEST_P(SDFFeatures_TEST, WorldWithNestedModelJointToWorld)
{
WorldPtr world = this->LoadWorld(
TEST_WORLD_DIR "/world_with_nested_model_joint_to_world.sdf");
const auto worldPath =
gz::common::testing::SourceFile(
"dartsim", "worlds", "world_with_nested_model_joint_to_world.sdf");
WorldPtr world = this->LoadWorld(worldPath);
ASSERT_NE(nullptr, world);
EXPECT_EQ(1u, world->GetModelCount());

Expand Down Expand Up @@ -690,7 +699,10 @@ TEST_P(SDFFeatures_TEST, WorldWithNestedModelJointToWorld)
// Test that joint type falls back to fixed if the type is not supported
TEST_P(SDFFeatures_TEST, FallbackToFixedJoint)
{
WorldPtr world = this->LoadWorld(TEST_WORLD_DIR"/test.world");
const auto worldPath =
gz::common::testing::SourceFile(
"dartsim", "worlds", "test.world");
WorldPtr world = this->LoadWorld(worldPath);
ASSERT_NE(nullptr, world);

dart::simulation::WorldPtr dartWorld = world->GetDartsimWorld();
Expand All @@ -716,8 +728,10 @@ TEST_P(SDFFeatures_TEST, FallbackToFixedJoint)
// Check that joints between links in different models work as expected
TEST_P(SDFFeatures_TEST, JointsAcrossNestedModels)
{
WorldPtr world = this->LoadWorld(
TEST_WORLD_DIR "/joint_across_nested_models.sdf");
const auto worldPath =
gz::common::testing::SourceFile(
"dartsim", "worlds", "joint_across_nested_models.sdf");
WorldPtr world = this->LoadWorld(worldPath);
ASSERT_NE(nullptr, world);

dart::simulation::WorldPtr dartWorld = world->GetDartsimWorld();
Expand Down Expand Up @@ -775,7 +789,10 @@ INSTANTIATE_TEST_SUITE_P(LoadWorld, SDFFeatures_FrameSemantics,
/////////////////////////////////////////////////
TEST_P(SDFFeatures_FrameSemantics, LinkRelativeTo)
{
WorldPtr world = this->LoadWorld(TEST_WORLD_DIR"/model_frames.sdf");
const auto worldPath =
gz::common::testing::SourceFile(
"dartsim", "worlds", "model_frames.sdf");
WorldPtr world = this->LoadWorld(worldPath);
ASSERT_NE(nullptr, world);
const std::string modelName = "link_relative_to";

Expand Down Expand Up @@ -807,7 +824,10 @@ TEST_P(SDFFeatures_FrameSemantics, LinkRelativeTo)
/////////////////////////////////////////////////
TEST_P(SDFFeatures_FrameSemantics, CollisionRelativeTo)
{
WorldPtr world = this->LoadWorld(TEST_WORLD_DIR"/model_frames.sdf");
const auto worldPath =
gz::common::testing::SourceFile(
"dartsim", "worlds", "model_frames.sdf");
WorldPtr world = this->LoadWorld(worldPath);
ASSERT_NE(nullptr, world);
const std::string modelName = "collision_relative_to";

Expand Down Expand Up @@ -844,7 +864,10 @@ TEST_P(SDFFeatures_FrameSemantics, CollisionRelativeTo)
/////////////////////////////////////////////////
TEST_P(SDFFeatures_FrameSemantics, ExplicitFramesWithLinks)
{
WorldPtr world = this->LoadWorld(TEST_WORLD_DIR"/model_frames.sdf");
const auto worldPath =
gz::common::testing::SourceFile(
"dartsim", "worlds", "model_frames.sdf");
WorldPtr world = this->LoadWorld(worldPath);
ASSERT_NE(nullptr, world);
const std::string modelName = "explicit_frames_with_links";

Expand Down Expand Up @@ -891,7 +914,10 @@ TEST_P(SDFFeatures_FrameSemantics, ExplicitFramesWithLinks)
/////////////////////////////////////////////////
TEST_P(SDFFeatures_FrameSemantics, ExplicitFramesWithCollision)
{
WorldPtr world = this->LoadWorld(TEST_WORLD_DIR"/model_frames.sdf");
const auto worldPath =
gz::common::testing::SourceFile(
"dartsim", "worlds", "model_frames.sdf");
WorldPtr world = this->LoadWorld(worldPath);
ASSERT_NE(nullptr, world);
const std::string modelName = "explicit_frames_with_collisions";

Expand Down Expand Up @@ -928,7 +954,10 @@ TEST_P(SDFFeatures_FrameSemantics, ExplicitFramesWithCollision)
/////////////////////////////////////////////////
TEST_P(SDFFeatures_FrameSemantics, ExplicitWorldFrames)
{
WorldPtr world = this->LoadWorld(TEST_WORLD_DIR"/world_frames.sdf");
const auto worldPath =
gz::common::testing::SourceFile(
"dartsim", "worlds", "world_frames.sdf");
WorldPtr world = this->LoadWorld(worldPath);
ASSERT_NE(nullptr, world);
const std::string modelName = "M";

Expand All @@ -938,7 +967,6 @@ TEST_P(SDFFeatures_FrameSemantics, ExplicitWorldFrames)
const dart::dynamics::SkeletonPtr skeleton =
dartWorld->getSkeleton(modelName);


ASSERT_NE(nullptr, skeleton);
ASSERT_EQ(1u, skeleton->getNumBodyNodes());

Expand All @@ -965,7 +993,10 @@ TEST_P(SDFFeatures_FrameSemantics, ExplicitWorldFrames)
/////////////////////////////////////////////////
TEST_P(SDFFeatures_TEST, Shapes)
{
auto world = this->LoadWorld(TEST_WORLD_DIR"/shapes.sdf");
const auto worldPath =
gz::common::testing::SourceFile(
"dartsim", "worlds", "shapes.sdf");
WorldPtr world = this->LoadWorld(worldPath);
ASSERT_NE(nullptr, world);

auto dartWorld = world->GetDartsimWorld();
Expand Down
12 changes: 8 additions & 4 deletions dartsim/src/WorldFeatures_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,8 @@
#include <gtest/gtest.h>

#include <gz/common/Console.hh>
#include <gz/common/testing/TestPaths.hh>

#include <gz/physics/FindFeatures.hh>
#include <gz/plugin/Loader.hh>
#include <gz/physics/RequestEngine.hh>
Expand Down Expand Up @@ -82,8 +84,9 @@ TestWorldPtr LoadWorld(
//////////////////////////////////////////////////
TEST_F(WorldFeaturesFixture, CollisionDetector)
{
auto world = LoadWorld(this->engine,
gz::common::joinPaths(TEST_WORLD_DIR, "empty.sdf"));
const auto worldPath =
gz::common::testing::SourceFile("dartsim", "worlds", "empty.sdf");
const auto world = LoadWorld(this->engine, worldPath);
EXPECT_EQ("ode", world->GetCollisionDetector());

world->SetCollisionDetector("banana");
Expand All @@ -105,8 +108,9 @@ TEST_F(WorldFeaturesFixture, CollisionDetector)
//////////////////////////////////////////////////
TEST_F(WorldFeaturesFixture, Solver)
{
auto world = LoadWorld(this->engine,
gz::common::joinPaths(TEST_WORLD_DIR, "empty.sdf"));
const auto worldPath =
gz::common::testing::SourceFile("dartsim", "worlds", "empty.sdf");
const auto world = LoadWorld(this->engine, worldPath);

EXPECT_EQ("DantzigBoxedLcpSolver", world->GetSolver());

Expand Down
2 changes: 1 addition & 1 deletion src/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@ gz_build_tests(
TYPE UNIT
SOURCES ${gtest_sources}
INCLUDE_DIRS
${PROJECT_SOURCE_DIR}/test)
${PROJECT_SOURCE_DIR}/test
ENVIRONMENT
GZ_PHYSICS_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX})

Expand Down
2 changes: 1 addition & 1 deletion test/common_test/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -67,8 +67,8 @@ foreach(test ${tests})
${PROJECT_SOURCE_DIR}/test)

target_compile_definitions(${test_executable} PRIVATE
"TEST_WORLD_DIR=\"${CMAKE_CURRENT_SOURCE_DIR}/worlds/\""
"GZ_PHYSICS_RESOURCE_DIR=\"${GZ_PHYSICS_RESOURCE_DIR}\""
"TESTING_PROJECT_SOURCE_DIR=\"${PROJECT_SOURCE_DIR}\""
)

install(TARGETS ${test_executable} DESTINATION ${TEST_INSTALL_DIR})
Expand Down
7 changes: 5 additions & 2 deletions test/common_test/added_mass.cc
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,8 @@
#include <gtest/gtest.h>

#include <gz/common/Console.hh>
#include <gz/common/testing/TestPaths.hh>

#include <gz/plugin/Loader.hh>

#include "TestLibLoader.hh"
Expand Down Expand Up @@ -85,9 +87,10 @@ 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(
gz::common::joinPaths(TEST_WORLD_DIR, "falling_added_mass.world"));
const sdf::Errors errors = root.Load(worldPath);
EXPECT_TRUE(errors.empty()) << errors;
const sdf::World *sdfWorld = root.WorldByIndex(0);
EXPECT_NE(nullptr, sdfWorld);
Expand Down
6 changes: 4 additions & 2 deletions test/common_test/detachable_joint.cc
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@
#include <chrono>

#include <gz/common/Console.hh>
#include <gz/common/testing/TestPaths.hh>
#include <gz/plugin/Loader.hh>

#include <gz/math/Helpers.hh>
Expand Down Expand Up @@ -109,9 +110,10 @@ TYPED_TEST(DetachableJointTest, CorrectAttachmentPoints)
gz::physics::RequestEngine3d<DetachableJointFeatureList>::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(
gz::common::joinPaths(TEST_WORLD_DIR, "detachable_joint.world"));
const sdf::Errors errors = root.Load(worldPath);
ASSERT_TRUE(errors.empty()) << errors.front();

auto world = engine->ConstructWorld(*root.WorldByIndex(0));
Expand Down
6 changes: 5 additions & 1 deletion test/common_test/joint_transmitted_wrench_features.cc
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,7 @@
#include <LinearMath/btScalar.h>

#include <gz/common/Console.hh>
#include <gz/common/testing/TestPaths.hh>
#include <gz/plugin/Loader.hh>

#include <gz/math/Helpers.hh>
Expand Down Expand Up @@ -102,8 +103,11 @@ class JointTransmittedWrenchFixture :
auto engine = gz::physics::RequestEngine3d<T>::From(plugin);
ASSERT_NE(nullptr, engine);

const auto worldPath =
gz::common::testing::TestFile(
"common_test", "worlds", "pendulum_joint_wrench.sdf");
sdf::Root root;
const sdf::Errors errors = root.Load(gz::common::joinPaths(TEST_WORLD_DIR, "pendulum_joint_wrench.sdf"));
const sdf::Errors errors = root.Load(worldPath);
ASSERT_TRUE(errors.empty()) << errors.front();

this->world = engine->ConstructWorld(*root.WorldByIndex(0));
Expand Down
1 change: 1 addition & 0 deletions test/integration/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,7 @@ gz_build_tests(
gz-plugin${GZ_PLUGIN_VER}::loader
INCLUDE_DIRS
${PROJECT_SOURCE_DIR}/src
${PROJECT_SOURCE_DIR}/test
TEST_LIST list
ENVIRONMENT
GZ_PHYSICS_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX})
Expand Down
1 change: 1 addition & 0 deletions test/performance/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,7 @@ gz_build_tests(
SOURCES ${tests}
INCLUDE_DIRS
${PROJECT_SOURCE_DIR}/src
${PROJECT_SOURCE_DIR}/test
ENVIRONMENT
GZ_PHYSICS_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX}
)
2 changes: 1 addition & 1 deletion tpe/plugin/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -57,6 +57,7 @@ gz_build_tests(
${features}
gz-plugin${GZ_PLUGIN_VER}::loader
gz-common${GZ_COMMON_VER}::gz-common${GZ_COMMON_VER}
gz-common${GZ_COMMON_VER}::testing
${PROJECT_LIBRARY_TARGET_NAME}-sdf
${PROJECT_LIBRARY_TARGET_NAME}-mesh
TEST_LIST tests
Expand All @@ -68,7 +69,6 @@ foreach(test ${tests})
target_include_directories(${test} PRIVATE ${tpelib_dir})
target_compile_definitions(${test} PRIVATE
"tpe_plugin_LIB=\"$<TARGET_FILE:${tpe_plugin}>\""
"TEST_WORLD_DIR=\"${CMAKE_CURRENT_SOURCE_DIR}/worlds/\""
"GZ_PHYSICS_RESOURCE_DIR=\"${GZ_PHYSICS_RESOURCE_DIR}\"")

endforeach()
10 changes: 8 additions & 2 deletions tpe/plugin/src/SDFFeatures_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,8 @@

#include <tuple>

#include <gz/common/testing/TestPaths.hh>

#include <sdf/Root.hh>
#include <sdf/World.hh>

Expand Down Expand Up @@ -90,7 +92,9 @@ World LoadWorld(const std::string &_world)
// Test that the tpe plugin loaded all the relevant information correctly.
TEST(SDFFeatures_TEST, CheckTpeData)
{
World world = LoadWorld(TEST_WORLD_DIR"/test.world");
const auto worldPath =
gz::common::testing::SourceFile("tpe", "plugin", "worlds", "test.world");
auto world = LoadWorld(worldPath);
auto tpeWorld = world.GetTpeLibWorld();
ASSERT_NE(nullptr, tpeWorld);

Expand Down Expand Up @@ -363,7 +367,9 @@ TEST(SDFFeatures_TEST, CheckTpeData)
// Test that the tpe plugin loaded nested models correctly.
TEST(SDFFeatures_TEST, NestedModel)
{
World world = LoadWorld(TEST_WORLD_DIR"/nested_model.world");
const auto worldPath =
gz::common::testing::SourceFile("tpe", "plugin", "worlds", "nested_model.world");
auto world = LoadWorld(worldPath);
auto tpeWorld = world.GetTpeLibWorld();
ASSERT_NE(nullptr, tpeWorld);

Expand Down
Loading

0 comments on commit ad7d7a4

Please sign in to comment.