Skip to content

Commit

Permalink
Garden test cleanup (#587)
Browse files Browse the repository at this point in the history
This cleans up physics tests in a few ways:

Consolidate TestUtilities.hh and test/Utils.hh
Move test headers to test/include/test
Move mock headers to test/include/mock
Create an INTERFACE library for test/mock headers that sets common compiler definitions as well as common libraries to link against
Remove all instances of hardcoded world names or resource names and instead use constants.

Signed-off-by: Michael Carroll <[email protected]>
Co-authored-by: Alejandro Hernández Cordero <[email protected]>
  • Loading branch information
mjcarroll and ahcorde authored Jan 30, 2024
1 parent 5367620 commit 8e1aca6
Show file tree
Hide file tree
Showing 77 changed files with 382 additions and 1,818 deletions.
5 changes: 3 additions & 2 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -42,6 +42,9 @@ gz_find_package(gz-common5
REQUIRED_BY heightmap mesh dartsim tpe tpelib bullet)
set(GZ_COMMON_VER ${gz-common5_VERSION_MAJOR})

# This is only used for test support
gz_find_package(gz-common5 REQUIRED COMPONENTS testing)

#--------------------------------------
# Find gz-math
gz_find_package(gz-math7 REQUIRED COMPONENTS eigen3)
Expand Down Expand Up @@ -90,8 +93,6 @@ gz_find_package(GzBullet

message(STATUS "-------------------------------------------\n")

set(GZ_PHYSICS_RESOURCE_DIR "${CMAKE_SOURCE_DIR}/resources")

# Plugin install dirs
set(GZ_PHYSICS_ENGINE_RELATIVE_INSTALL_DIR
${GZ_LIB_INSTALL_DIR}/gz-${GZ_DESIGNATION}-${PROJECT_VERSION_MAJOR}/engine-plugins
Expand Down
20 changes: 6 additions & 14 deletions dartsim/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -84,22 +84,21 @@ gz_build_tests(
LIB_DEPS
${features}
${dartsim_plugin}
gz-plugin${GZ_PLUGIN_VER}::loader
gz-common${GZ_COMMON_VER}::gz-common${GZ_COMMON_VER}
gz-physics-test
gz-common${GZ_COMMON_VER}::geospatial
${PROJECT_LIBRARY_TARGET_NAME}-sdf
${PROJECT_LIBRARY_TARGET_NAME}-heightmap
${PROJECT_LIBRARY_TARGET_NAME}-mesh
TEST_LIST tests
ENVIRONMENT
GZ_PHYSICS_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX})
GZ_PHYSICS_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX}
INCLUDE_DIRS
${CMAKE_CURRENT_SOURCE_DIR}/src
)

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}\"")
"dartsim_plugin_LIB=\"$<TARGET_FILE:${dartsim_plugin}>\"")

if (DART_HAS_CONTACT_SURFACE_HEADER)
target_compile_definitions(${test} PRIVATE DART_HAS_CONTACT_SURFACE)
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()
3 changes: 2 additions & 1 deletion dartsim/src/AddedMassFeatures_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -39,6 +39,7 @@
#include <sdf/World.hh>

#include <test/Utils.hh>
#include "Worlds.hh"

struct TestFeatureList : gz::physics::FeatureList<
gz::physics::GetEntities,
Expand Down Expand Up @@ -121,7 +122,7 @@ 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 world = LoadWorld(dartsim::worlds::kAddedMassSdf);
ASSERT_NE(nullptr, world);

auto dartWorld = world->GetDartsimWorld();
Expand Down
5 changes: 3 additions & 2 deletions dartsim/src/Base_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -38,8 +38,9 @@
#include "EntityManagementFeatures.hh"
#include "SDFFeatures.hh"

using namespace gz::physics;
#include "test/Resources.hh"

using namespace gz::physics;


TEST(BaseClass, RemoveModel)
Expand Down Expand Up @@ -166,7 +167,7 @@ TEST(BaseClass, SdfConstructionBookkeeping)

::sdf::Root root;

auto errors = root.Load(GZ_PHYSICS_RESOURCE_DIR "/rrbot.xml");
auto errors = root.Load(gz::physics::test::resources::kRrbotXml);
ASSERT_TRUE(errors.empty());
const ::sdf::Model *sdfModel = root.Model();
ASSERT_NE(nullptr, sdfModel);
Expand Down
11 changes: 5 additions & 6 deletions dartsim/src/EntityManagement_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -35,6 +35,8 @@
#include "KinematicsFeatures.hh"
#include "ShapeFeatures.hh"

#include "test/Resources.hh"

using namespace gz;

struct TestFeatureList : physics::FeatureList<
Expand Down Expand Up @@ -172,8 +174,7 @@ TEST(EntityManagement_TEST, ConstructEmptyWorld)
auto meshLink = model->ConstructEmptyLink("mesh_link");
meshLink->AttachFixedJoint(child, "fixed");

const std::string meshFilename = common::joinPaths(
GZ_PHYSICS_RESOURCE_DIR, "chassis.dae");
const std::string meshFilename = gz::physics::test::resources::kChassisDae;
auto &meshManager = *common::MeshManager::Instance();
auto *mesh = meshManager.Load(meshFilename);

Expand Down Expand Up @@ -212,8 +213,7 @@ TEST(EntityManagement_TEST, ConstructEmptyWorld)
auto heightmapLink = model->ConstructEmptyLink("heightmap_link");
heightmapLink->AttachFixedJoint(child, "heightmap_joint");

auto heightmapFilename = common::joinPaths(
GZ_PHYSICS_RESOURCE_DIR, "heightmap_bowl.png");
auto heightmapFilename = gz::physics::test::resources::kHeightmapBowlPng;
common::ImageHeightmap data;
EXPECT_EQ(0, data.Load(heightmapFilename));

Expand All @@ -239,8 +239,7 @@ TEST(EntityManagement_TEST, ConstructEmptyWorld)
auto demLink = model->ConstructEmptyLink("dem_link");
demLink->AttachFixedJoint(child, "dem_joint");

auto demFilename = common::joinPaths(
GZ_PHYSICS_RESOURCE_DIR, "volcano.tif");
auto demFilename = gz::physics::test::resources::kVolcanoTif;
common::Dem dem;
EXPECT_EQ(0, dem.Load(demFilename));

Expand Down
29 changes: 15 additions & 14 deletions dartsim/src/SDFFeatures_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -53,6 +53,8 @@
#include <sdf/World.hh>

#include <test/Utils.hh>
#include <test/common_test/Worlds.hh>
#include "Worlds.hh"

using namespace gz;

Expand Down Expand Up @@ -313,7 +315,7 @@ 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");
WorldPtr world = this->LoadWorld(common_test::worlds::kTestWorld);
ASSERT_NE(nullptr, world);

dart::simulation::WorldPtr dartWorld = world->GetDartsimWorld();
Expand Down Expand Up @@ -421,7 +423,7 @@ 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");
WorldPtr world = this->LoadWorld(common_test::worlds::kTestWorld);
ASSERT_NE(nullptr, world);

dart::simulation::WorldPtr dartWorld = world->GetDartsimWorld();
Expand Down Expand Up @@ -581,7 +583,7 @@ TEST_P(SDFFeatures_TEST, WorldIsParentOrChild)
TEST_P(SDFFeatures_TEST, WorldWithNestedModel)
{
WorldPtr world =
this->LoadWorld(TEST_WORLD_DIR "/world_with_nested_model.sdf");
this->LoadWorld(common_test::worlds::kWorldWithNestedModelSdf);
ASSERT_NE(nullptr, world);
EXPECT_EQ(2u, world->GetModelCount());

Expand Down Expand Up @@ -646,7 +648,7 @@ 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");
dartsim::worlds::kWorldWithNestedModelJointToWorldSdf);
ASSERT_NE(nullptr, world);
EXPECT_EQ(1u, world->GetModelCount());

Expand Down Expand Up @@ -690,7 +692,7 @@ 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");
WorldPtr world = this->LoadWorld(common_test::worlds::kTestWorld);
ASSERT_NE(nullptr, world);

dart::simulation::WorldPtr dartWorld = world->GetDartsimWorld();
Expand All @@ -717,7 +719,7 @@ TEST_P(SDFFeatures_TEST, FallbackToFixedJoint)
TEST_P(SDFFeatures_TEST, JointsAcrossNestedModels)
{
WorldPtr world = this->LoadWorld(
TEST_WORLD_DIR "/joint_across_nested_models.sdf");
dartsim::worlds::kJointAcrossNestedModelsSdf);
ASSERT_NE(nullptr, world);

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

Expand Down Expand Up @@ -807,7 +809,7 @@ TEST_P(SDFFeatures_FrameSemantics, LinkRelativeTo)
/////////////////////////////////////////////////
TEST_P(SDFFeatures_FrameSemantics, CollisionRelativeTo)
{
WorldPtr world = this->LoadWorld(TEST_WORLD_DIR"/model_frames.sdf");
WorldPtr world = this->LoadWorld(dartsim::worlds::kModelFramesSdf);
ASSERT_NE(nullptr, world);
const std::string modelName = "collision_relative_to";

Expand Down Expand Up @@ -844,7 +846,7 @@ TEST_P(SDFFeatures_FrameSemantics, CollisionRelativeTo)
/////////////////////////////////////////////////
TEST_P(SDFFeatures_FrameSemantics, ExplicitFramesWithLinks)
{
WorldPtr world = this->LoadWorld(TEST_WORLD_DIR"/model_frames.sdf");
WorldPtr world = this->LoadWorld(dartsim::worlds::kModelFramesSdf);
ASSERT_NE(nullptr, world);
const std::string modelName = "explicit_frames_with_links";

Expand Down Expand Up @@ -891,7 +893,7 @@ TEST_P(SDFFeatures_FrameSemantics, ExplicitFramesWithLinks)
/////////////////////////////////////////////////
TEST_P(SDFFeatures_FrameSemantics, ExplicitFramesWithCollision)
{
WorldPtr world = this->LoadWorld(TEST_WORLD_DIR"/model_frames.sdf");
WorldPtr world = this->LoadWorld(dartsim::worlds::kModelFramesSdf);
ASSERT_NE(nullptr, world);
const std::string modelName = "explicit_frames_with_collisions";

Expand Down Expand Up @@ -928,7 +930,7 @@ TEST_P(SDFFeatures_FrameSemantics, ExplicitFramesWithCollision)
/////////////////////////////////////////////////
TEST_P(SDFFeatures_FrameSemantics, ExplicitWorldFrames)
{
WorldPtr world = this->LoadWorld(TEST_WORLD_DIR"/world_frames.sdf");
WorldPtr world = this->LoadWorld(dartsim::worlds::kWorldFramesSdf);
ASSERT_NE(nullptr, world);
const std::string modelName = "M";

Expand All @@ -938,7 +940,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 +966,7 @@ TEST_P(SDFFeatures_FrameSemantics, ExplicitWorldFrames)
/////////////////////////////////////////////////
TEST_P(SDFFeatures_TEST, Shapes)
{
auto world = this->LoadWorld(TEST_WORLD_DIR"/shapes.sdf");
WorldPtr world = this->LoadWorld(common_test::worlds::kShapesWorld);
ASSERT_NE(nullptr, world);

auto dartWorld = world->GetDartsimWorld();
Expand All @@ -974,7 +975,7 @@ TEST_P(SDFFeatures_TEST, Shapes)
ASSERT_EQ(5u, dartWorld->getNumSkeletons());

int count{0};
for (auto name : {"box", "cylinder", "sphere", "capsule", "ellipsoid"})
for (auto name : {"sphere", "box", "cylinder", "capsule", "ellipsoid"})
{
const auto skeleton = dartWorld->getSkeleton(count++);
ASSERT_NE(nullptr, skeleton);
Expand Down
7 changes: 3 additions & 4 deletions dartsim/src/WorldFeatures_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -32,6 +32,7 @@
#include <sdf/World.hh>

#include "test/Utils.hh"
#include "test/common_test/Worlds.hh"

struct TestFeatureList : gz::physics::FeatureList<
gz::physics::CollisionDetector,
Expand Down Expand Up @@ -82,8 +83,7 @@ TestWorldPtr LoadWorld(
//////////////////////////////////////////////////
TEST_F(WorldFeaturesFixture, CollisionDetector)
{
auto world = LoadWorld(this->engine,
gz::common::joinPaths(TEST_WORLD_DIR, "empty.sdf"));
const auto world = LoadWorld(this->engine, common_test::worlds::kEmptySdf);
EXPECT_EQ("ode", world->GetCollisionDetector());

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

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

Expand Down
43 changes: 43 additions & 0 deletions dartsim/src/Worlds.hh
Original file line number Diff line number Diff line change
@@ -0,0 +1,43 @@
/*
* 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 DARTSIM_WORLDS_HH_
#define DARTSIM_WORLDS_HH_

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

#include <string>

// \brief retrieve a filename from the dartsim/worlds directory
// \param[in] _world filename to retrieve
// \return full path to the request world
inline std::string DartsimTestWorld(const std::string &_world)
{
return gz::common::testing::SourceFile("dartsim", "worlds", _world);
}

namespace dartsim::worlds
{
const auto kAddedMassSdf = DartsimTestWorld("added_mass.sdf");
const auto kJointAcrossNestedModelsSdf =
DartsimTestWorld("joint_across_nested_models.sdf");
const auto kModelFramesSdf = DartsimTestWorld("model_frames.sdf");
const auto kWorldFramesSdf = DartsimTestWorld("world_frames.sdf");
const auto kWorldWithNestedModelJointToWorldSdf =
DartsimTestWorld("world_with_nested_model_joint_to_world.sdf");
} // namespace dartsim::worlds
#endif // DARTSIM_WORLDS_HH_
5 changes: 0 additions & 5 deletions dartsim/worlds/empty.sdf

This file was deleted.

Loading

0 comments on commit 8e1aca6

Please sign in to comment.