Skip to content

Commit

Permalink
add unit test for world conversion
Browse files Browse the repository at this point in the history
Signed-off-by: Ashton Larkin <[email protected]>
  • Loading branch information
adlarkin committed Jan 11, 2022
1 parent 18f3ac1 commit 3bbd6ea
Show file tree
Hide file tree
Showing 4 changed files with 117 additions and 2 deletions.
21 changes: 21 additions & 0 deletions test/test_utils.hh
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,9 @@
#define SDF_TEST_UTILS_HH_

#include <ostream>
#include <string>
#include "sdf/Console.hh"
#include "sdf/Root.hh"

namespace sdf
{
Expand Down Expand Up @@ -104,6 +106,25 @@ class RedirectConsoleStream
private: sdf::Console::ConsoleStream oldStream;
};

/// \brief Load an SDF file into a sdf::Root object
/// \param[in] _fileName The name of the file to load
/// \param[in] _root The sdf::Root object to load the file into
/// \return True if a file named _fileName was successfully loaded into
/// _root. False otherwise
bool LoadSdfFile(const std::string &_fileName, sdf::Root &_root)
{
auto errors = _root.Load(_fileName);
if (!errors.empty())
{
std::cerr << "Errors encountered:\n";
for (const auto &e : errors)
std::cerr << e << "\n";
return false;
}

return true;
}

} // namespace testing
} // namespace sdf

Expand Down
7 changes: 6 additions & 1 deletion usd/src/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,11 @@ target_link_libraries(${usd_target}
)

# Build the unit tests
ign_build_tests(TYPE UNIT SOURCES ${gtest_sources} LIB_DEPS ${usd_target})
ign_build_tests(
TYPE UNIT
SOURCES ${gtest_sources}
LIB_DEPS ${usd_target}
INCLUDE_DIRS ${PROJECT_SOURCE_DIR}/test
)

add_subdirectory(cmd)
4 changes: 3 additions & 1 deletion usd/src/World.cc
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,9 @@ namespace usd
static_cast<float>(sdfWorldGravity.Length()));

// TODO(ahcorde) Add parser
std::cerr << "Parser for a sdf world is not yet implemented\n";
std::cerr << "Parser for a sdf world only parses physics information at "
<< "the moment. Models and lights that are children of the world "
<< "are currently being ignored.\n";

return true;
}
Expand Down
87 changes: 87 additions & 0 deletions usd/src/World_Sdf2Usd_TEST.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1,87 @@
/*
* Copyright 2022 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.
*
*/

#include <string>

#include <gtest/gtest.h>
#include <pxr/base/gf/vec3f.h>
#include <pxr/base/tf/token.h>
#include <pxr/usd/usd/prim.h>
#include <pxr/usd/usd/primRange.h>
#include <pxr/usd/usd/stage.h>
#include <pxr/usd/usdGeom/tokens.h>
#include <pxr/usd/usdPhysics/scene.h>

#include "sdf/usd/World.hh"
#include "sdf/Root.hh"
#include "test_config.h"
#include "test_utils.hh"

/////////////////////////////////////////////////
// Fixture that creates a USD stage for each test case.
class UsdStageFixture : public::testing::Test
{
public: UsdStageFixture() = default;

protected: void SetUp() override
{
this->stage = pxr::UsdStage::CreateInMemory();
ASSERT_TRUE(this->stage);
}

public: pxr::UsdStageRefPtr stage;
};

/////////////////////////////////////////////////
TEST_F(UsdStageFixture, World)
{
const auto path = sdf::testing::TestFile("sdf", "empty.sdf");
sdf::Root root;

ASSERT_TRUE(sdf::testing::LoadSdfFile(path, root));
ASSERT_EQ(1u, root.WorldCount());
auto world = root.WorldByIndex(0u);

const auto worldPath = std::string("/" + world->Name());
EXPECT_TRUE(usd::ParseSdfWorld(*world, this->stage, worldPath));

// check top-level stage information
EXPECT_DOUBLE_EQ(100.0, this->stage->GetEndTimeCode());
EXPECT_DOUBLE_EQ(0.0, this->stage->GetStartTimeCode());
EXPECT_DOUBLE_EQ(24.0, this->stage->GetTimeCodesPerSecond());
pxr::TfToken upAxisVal;
EXPECT_TRUE(this->stage->GetMetadata(pxr::UsdGeomTokens->upAxis, &upAxisVal));
EXPECT_EQ(pxr::UsdGeomTokens->z, upAxisVal);
double metersPerUnitVal;
EXPECT_TRUE(this->stage->GetMetadata(pxr::TfToken("metersPerUnit"),
&metersPerUnitVal));
EXPECT_DOUBLE_EQ(1.0, metersPerUnitVal);

// Check that world prim exists, and that things like physics information
// were parsed correctly
auto worldPrim = this->stage->GetPrimAtPath(pxr::SdfPath(worldPath));
ASSERT_TRUE(worldPrim);
auto physicsScene = pxr::UsdPhysicsScene::Get(this->stage,
pxr::SdfPath(worldPath + "/physics"));
ASSERT_TRUE(physicsScene);
pxr::GfVec3f gravityDirectionVal;
EXPECT_TRUE(physicsScene.GetGravityDirectionAttr().Get(&gravityDirectionVal));
EXPECT_EQ(gravityDirectionVal, pxr::GfVec3f(0, 0, -1));
float gravityMagnitudeVal;
EXPECT_TRUE(physicsScene.GetGravityMagnitudeAttr().Get(&gravityMagnitudeVal));
EXPECT_FLOAT_EQ(gravityMagnitudeVal, 9.8f);
}

0 comments on commit 3bbd6ea

Please sign in to comment.