Skip to content

Commit

Permalink
Move resources and add constants
Browse files Browse the repository at this point in the history
Signed-off-by: Michael Carroll <[email protected]>
  • Loading branch information
mjcarroll committed Jan 9, 2024
1 parent 19fcc79 commit 2d36397
Show file tree
Hide file tree
Showing 33 changed files with 195 additions and 149 deletions.
2 changes: 0 additions & 2 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -92,8 +92,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
8 changes: 5 additions & 3 deletions dartsim/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -91,12 +91,14 @@ gz_build_tests(
${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}>\""
"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 Down
6 changes: 2 additions & 4 deletions dartsim/src/AddedMassFeatures_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,6 @@
#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 All @@ -41,6 +40,7 @@
#include <sdf/World.hh>

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

struct TestFeatureList : gz::physics::FeatureList<
gz::physics::GetEntities,
Expand Down Expand Up @@ -123,9 +123,7 @@ TEST(AddedMassFeatures, AddedMass)
0, 0, 0, 0, 1, 0,
0, 0, 0, 0, 0, 1;

const auto worldPath =
gz::common::testing::SourceFile("dartsim", "worlds", "added_mass.sdf");
const auto world = LoadWorld(worldPath);
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
61 changes: 15 additions & 46 deletions dartsim/src/SDFFeatures_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -54,6 +54,7 @@
#include <sdf/World.hh>

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

using namespace gz;

Expand Down Expand Up @@ -314,9 +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)
{
const auto worldPath =
gz::common::testing::SourceFile("dartsim", "worlds", "test.world");
WorldPtr world = this->LoadWorld(worldPath);
WorldPtr world = this->LoadWorld(dartsim::worlds::kTestWorld);
ASSERT_NE(nullptr, world);

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

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

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

Expand Down Expand Up @@ -699,10 +691,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)
{
const auto worldPath =
gz::common::testing::SourceFile(
"dartsim", "worlds", "test.world");
WorldPtr world = this->LoadWorld(worldPath);
WorldPtr world = this->LoadWorld(dartsim::worlds::kTestWorld);
ASSERT_NE(nullptr, world);

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

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

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

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

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

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

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

auto dartWorld = world->GetDartsimWorld();
Expand Down
10 changes: 3 additions & 7 deletions dartsim/src/WorldFeatures_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,6 @@
#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>
Expand All @@ -34,6 +33,7 @@
#include <sdf/World.hh>

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

struct TestFeatureList : gz::physics::FeatureList<
gz::physics::CollisionDetector,
Expand Down Expand Up @@ -84,9 +84,7 @@ TestWorldPtr LoadWorld(
//////////////////////////////////////////////////
TEST_F(WorldFeaturesFixture, CollisionDetector)
{
const auto worldPath =
gz::common::testing::SourceFile("dartsim", "worlds", "empty.sdf");
const auto world = LoadWorld(this->engine, worldPath);
const auto world = LoadWorld(this->engine, dartsim::worlds::kEmptySdf);
EXPECT_EQ("ode", world->GetCollisionDetector());

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

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

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

inline std::string DartsimTestWorld(const std::string &_world)
{
return gz::common::testing::TestFile("dartsim", "worlds", _world);
}

namespace dartsim::worlds
{
const auto kAddedMassSdf = DartsimTestWorld("added_mass.sdf");
const auto kEmptySdf = DartsimTestWorld("empty.sdf");
const auto kFallingWorld = DartsimTestWorld("falling.world");
const auto kJointAcrossNestedModelsSdf =
DartsimTestWorld("joint_across_nested_models.sdf");
const auto kModelFramesSdf = DartsimTestWorld("kModelFrames.sdf");
const auto kShapesWorld = DartsimTestWorld("shapes.world");
const auto kShapesBitmaskWorld = DartsimTestWorld("shapes_bitmask.sdf");
const auto kTestWorld = DartsimTestWorld("test.world");
const auto kWorldFramesSdf = DartsimTestWorld("world_frames.sdf");
const auto kWorldWithNestedModelSdf =
DartsimTestWorld("world_with_nested_model.sdf");
const auto kWorldWithNestedModelJointToWorldSdf =
DartsimTestWorld("world_with_nested_model_joint_to_world.sdf");

} // namespace dartsim::worlds
#endif // DARTSIM_WORLDS_HH_
2 changes: 0 additions & 2 deletions test/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -19,11 +19,9 @@ 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
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@ inline std::string CommonTestWorld(const std::string &_world)
return gz::common::testing::TestFile("common_test", "worlds", _world);
}

namespace worlds
namespace common_test::worlds
{
const auto kContactSdf = CommonTestWorld("contact.sdf");
const auto kDetachableJointWorld = CommonTestWorld("detachable_joint.world");
Expand All @@ -50,5 +50,5 @@ 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
} // namespace common_test::worlds
#endif // COMMON_TEST_WORLDS_WORLDS_HH_
5 changes: 3 additions & 2 deletions test/common_test/added_mass.cc
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@

#include "test/TestLibLoader.hh"
#include "test/Utils.hh"
#include "worlds/Worlds.hh"
#include "Worlds.hh"

#include <gz/physics/AddedMass.hh>
#include <gz/physics/FindFeatures.hh>
Expand Down Expand Up @@ -88,7 +88,8 @@ TEST_F(AddedMassFeaturesTest, Gravity)
std::string::npos);

sdf::Root root;
const sdf::Errors errors = root.Load(worlds::kFallingAddedMassWorld);
const sdf::Errors errors = root.Load(
common_test::worlds::kFallingAddedMassWorld);
EXPECT_TRUE(errors.empty()) << errors;
const sdf::World *sdfWorld = root.WorldByIndex(0);
EXPECT_NE(nullptr, sdfWorld);
Expand Down
Loading

0 comments on commit 2d36397

Please sign in to comment.