Skip to content

Commit 3b292c6

Browse files
committed
Merge branch 'sdf12' into adlarkin/add_lights_to_usd_cmake
Signed-off-by: Ashton Larkin <42042756+adlarkin@users.noreply.github.com>
2 parents 5d2c902 + c80d78d commit 3b292c6

File tree

8 files changed

+341
-6
lines changed

8 files changed

+341
-6
lines changed

.github/ci/before_cmake.sh

-2
Original file line numberDiff line numberDiff line change
@@ -25,7 +25,6 @@ then
2525

2626
wget https://github.com/PixarAnimationStudios/USD/archive/refs/tags/v21.11.zip
2727
unzip v21.11.zip
28-
sed -i '2059 i \ \ \ \ requiredDependencies.remove(BOOST)' USD-21.11/build_scripts/build_usd.py
2928
cd USD-21.11
3029
mkdir build
3130
cd build
@@ -47,7 +46,6 @@ then
4746
-DPXR_BUILD_ALEMBIC_PLUGIN=OFF \
4847
-DPXR_BUILD_DRACO_PLUGIN=OFF \
4948
-DPXR_ENABLE_MATERIALX_SUPPORT=OFF \
50-
-DBoost_NO_BOOST_CMAKE=On \
5149
-DBoost_INCLUDE_DIR=/usr/include \
5250
-DBoost_NO_BOOST_CMAKE=FALSE \
5351
..

.github/ci/packages.apt

+1
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,6 @@
11
libignition-common4-dev
22
libignition-cmake2-dev
3+
libignition-common4-dev
34
libignition-math6-dev
45
libignition-tools-dev
56
libignition-utils1-dev
+57
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,57 @@
1+
/*
2+
* Copyright (C) 2022 Open Source Robotics Foundation
3+
*
4+
* Licensed under the Apache License, Version 2.0 (the "License");
5+
* you may not use this file except in compliance with the License.
6+
* You may obtain a copy of the License at
7+
*
8+
* http://www.apache.org/licenses/LICENSE-2.0
9+
*
10+
* Unless required by applicable law or agreed to in writing, software
11+
* distributed under the License is distributed on an "AS IS" BASIS,
12+
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13+
* See the License for the specific language governing permissions and
14+
* limitations under the License.
15+
*
16+
*/
17+
18+
#ifndef SDF_USD_SDF_PARSER_WORLD_HH_
19+
#define SDF_USD_SDF_PARSER_WORLD_HH_
20+
21+
#include <string>
22+
23+
// TODO(ahcorde):this is to remove deprecated "warnings" in usd, these warnings
24+
// are reported using #pragma message so normal diagnostic flags cannot remove
25+
// them. This workaround requires this block to be used whenever usd is
26+
// included.
27+
#pragma push_macro ("__DEPRECATED")
28+
#undef __DEPRECATED
29+
#include <pxr/usd/usd/stage.h>
30+
#pragma pop_macro ("__DEPRECATED")
31+
32+
#include "sdf/config.hh"
33+
#include "sdf/system_util.hh"
34+
#include "sdf/World.hh"
35+
36+
namespace sdf
37+
{
38+
// Inline bracke to help doxygen filtering.
39+
inline namespace SDF_VERSION_NAMESPACE {
40+
//
41+
namespace usd
42+
{
43+
/// \brief Parse an SDF world into a USD stage.
44+
/// \param[in] _world The SDF world to parse.
45+
/// \param[in] _stage The stage that should contain the USD representation
46+
/// of _world. It must be initialized first
47+
/// \param[in] _path The USD path of the parsed world in _stage, which must be
48+
/// a valid USD path.
49+
/// \return Errors, which is a vector of Error objects. Each Error includes
50+
/// an error code and message. An empty vector indicates no error.
51+
sdf::Errors SDFORMAT_VISIBLE ParseSdfWorld(const sdf::World &_world,
52+
pxr::UsdStageRefPtr &_stage, const std::string &_path);
53+
}
54+
}
55+
}
56+
57+
#endif

usd/src/CMakeLists.txt

+8-3
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,6 @@
1-
# Collect source files into the "sources" variable and unit test files into the
2-
# "gtest_sources" variable.
3-
ign_get_libsources_and_unittests(sources gtest_sources)
1+
set(sources
2+
sdf_parser/World.cc
3+
)
44

55
ign_add_component(usd SOURCES ${sources} GET_TARGET_NAME usd_target)
66

@@ -15,6 +15,11 @@ target_link_libraries(${usd_target}
1515
${PXR_LIBRARIES}
1616
)
1717

18+
set(gtest_sources
19+
sdf_parser/sdf2usd_TEST.cc
20+
sdf_parser/World_Sdf2Usd_TEST.cc
21+
)
22+
1823
# Build the unit tests
1924
ign_build_tests(
2025
TYPE UNIT

usd/src/cmd/sdf2usd.cc

+5-1
Original file line numberDiff line numberDiff line change
@@ -17,14 +17,18 @@
1717

1818
#include <string.h>
1919

20+
// TODO(ahcorde):this is to remove deprecated "warnings" in usd, these warnings
21+
// are reported using #pragma message so normal diagnostic flags cannot remove
22+
// them. This workaround requires this block to be used whenever usd is
23+
// included.
2024
#include <ignition/utils/cli/CLI.hpp>
2125
#pragma push_macro ("__DEPRECATED")
2226
#undef __DEPRECATED
2327
#include <pxr/usd/usd/stage.h>
2428
#pragma pop_macro ("__DEPRECATED")
2529

2630
#include "sdf/sdf.hh"
27-
#include "sdf/usd/World.hh"
31+
#include "sdf/usd/sdf_parser/World.hh"
2832

2933
//////////////////////////////////////////////////
3034
/// \brief Enumeration of available commands

usd/src/sdf_parser/World.cc

+77
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,77 @@
1+
/*
2+
* Copyright (C) 2022 Open Source Robotics Foundation
3+
*
4+
* Licensed under the Apache License, Version 2.0 (the "License");
5+
* you may not use this file except in compliance with the License.
6+
* You may obtain a copy of the License at
7+
*
8+
* http://www.apache.org/licenses/LICENSE-2.0
9+
*
10+
* Unless required by applicable law or agreed to in writing, software
11+
* distributed under the License is distributed on an "AS IS" BASIS,
12+
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13+
* See the License for the specific language governing permissions and
14+
* limitations under the License.
15+
*
16+
*/
17+
18+
#include "sdf/usd/sdf_parser/World.hh"
19+
20+
#include <iostream>
21+
#include <string>
22+
23+
// TODO(ahcorde):this is to remove deprecated "warnings" in usd, these warnings
24+
// are reported using #pragma message so normal diagnostic flags cannot remove
25+
// them. This workaround requires this block to be used whenever usd is
26+
// included.
27+
#pragma push_macro ("__DEPRECATED")
28+
#undef __DEPRECATED
29+
#include <pxr/base/gf/vec3f.h>
30+
#include <pxr/usd/sdf/path.h>
31+
#include <pxr/usd/usd/prim.h>
32+
#include <pxr/usd/usd/stage.h>
33+
#include <pxr/usd/usdGeom/tokens.h>
34+
#include <pxr/usd/usdPhysics/scene.h>
35+
#pragma pop_macro ("__DEPRECATED")
36+
37+
#include "sdf/World.hh"
38+
39+
namespace sdf
40+
{
41+
// Inline bracke to help doxygen filtering.
42+
inline namespace SDF_VERSION_NAMESPACE {
43+
//
44+
namespace usd
45+
{
46+
sdf::Errors ParseSdfWorld(const sdf::World &_world, pxr::UsdStageRefPtr &_stage,
47+
const std::string &_path)
48+
{
49+
sdf::Errors errors;
50+
_stage->SetMetadata(pxr::UsdGeomTokens->upAxis, pxr::UsdGeomTokens->z);
51+
_stage->SetEndTimeCode(100);
52+
_stage->SetMetadata(pxr::TfToken("metersPerUnit"), 1.0);
53+
_stage->SetStartTimeCode(0);
54+
_stage->SetTimeCodesPerSecond(24);
55+
56+
const pxr::SdfPath worldPrimPath(_path);
57+
auto usdWorldPrim = _stage->DefinePrim(worldPrimPath);
58+
59+
auto usdPhysics = pxr::UsdPhysicsScene::Define(_stage,
60+
pxr::SdfPath(_path + "/physics"));
61+
const auto &sdfWorldGravity = _world.Gravity();
62+
const auto normalizedGravity = sdfWorldGravity.Normalized();
63+
usdPhysics.CreateGravityDirectionAttr().Set(pxr::GfVec3f(
64+
normalizedGravity.X(), normalizedGravity.Y(), normalizedGravity.Z()));
65+
usdPhysics.CreateGravityMagnitudeAttr().Set(
66+
static_cast<float>(sdfWorldGravity.Length()));
67+
68+
// TODO(ahcorde) Add parser
69+
std::cerr << "Parser for a sdf world only parses physics information at "
70+
<< "the moment. Models and lights that are children of the world "
71+
<< "are currently being ignored.\n";
72+
73+
return errors;
74+
}
75+
}
76+
}
77+
}
+96
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,96 @@
1+
/*
2+
* Copyright 2022 Open Source Robotics Foundation
3+
*
4+
* Licensed under the Apache License, Version 2.0 (the "License");
5+
* you may not use this file except in compliance with the License.
6+
* You may obtain a copy of the License at
7+
*
8+
* http://www.apache.org/licenses/LICENSE-2.0
9+
*
10+
* Unless required by applicable law or agreed to in writing, software
11+
* distributed under the License is distributed on an "AS IS" BASIS,
12+
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13+
* See the License for the specific language governing permissions and
14+
* limitations under the License.
15+
*
16+
*/
17+
18+
#include <string>
19+
20+
#include <gtest/gtest.h>
21+
22+
// TODO(ahcorde):this is to remove deprecated "warnings" in usd, these warnings
23+
// are reported using #pragma message so normal diagnostic flags cannot remove
24+
// them. This workaround requires this block to be used whenever usd is
25+
// included.
26+
#pragma push_macro ("__DEPRECATED")
27+
#undef __DEPRECATED
28+
#include <pxr/base/gf/vec3f.h>
29+
#include <pxr/base/tf/token.h>
30+
#include <pxr/usd/usd/prim.h>
31+
#include <pxr/usd/usd/primRange.h>
32+
#include <pxr/usd/usd/stage.h>
33+
#include <pxr/usd/usdGeom/tokens.h>
34+
#include <pxr/usd/usdPhysics/scene.h>
35+
#pragma pop_macro ("__DEPRECATED")
36+
37+
#include "sdf/usd/sdf_parser/World.hh"
38+
#include "sdf/Root.hh"
39+
#include "test_config.h"
40+
#include "test_utils.hh"
41+
42+
/////////////////////////////////////////////////
43+
// Fixture that creates a USD stage for each test case.
44+
class UsdStageFixture : public::testing::Test
45+
{
46+
public: UsdStageFixture() = default;
47+
48+
protected: void SetUp() override
49+
{
50+
this->stage = pxr::UsdStage::CreateInMemory();
51+
ASSERT_TRUE(this->stage);
52+
}
53+
54+
public: pxr::UsdStageRefPtr stage;
55+
};
56+
57+
/////////////////////////////////////////////////
58+
TEST_F(UsdStageFixture, World)
59+
{
60+
const auto path = sdf::testing::TestFile("sdf", "empty.sdf");
61+
sdf::Root root;
62+
63+
ASSERT_TRUE(sdf::testing::LoadSdfFile(path, root));
64+
ASSERT_EQ(1u, root.WorldCount());
65+
auto world = root.WorldByIndex(0u);
66+
67+
const auto worldPath = std::string("/" + world->Name());
68+
auto usdErrors = sdf::usd::ParseSdfWorld(*world, stage, worldPath);
69+
EXPECT_TRUE(usdErrors.empty());
70+
71+
// check top-level stage information
72+
EXPECT_DOUBLE_EQ(100.0, this->stage->GetEndTimeCode());
73+
EXPECT_DOUBLE_EQ(0.0, this->stage->GetStartTimeCode());
74+
EXPECT_DOUBLE_EQ(24.0, this->stage->GetTimeCodesPerSecond());
75+
pxr::TfToken upAxisVal;
76+
EXPECT_TRUE(this->stage->GetMetadata(pxr::UsdGeomTokens->upAxis, &upAxisVal));
77+
EXPECT_EQ(pxr::UsdGeomTokens->z, upAxisVal);
78+
double metersPerUnitVal;
79+
EXPECT_TRUE(this->stage->GetMetadata(pxr::TfToken("metersPerUnit"),
80+
&metersPerUnitVal));
81+
EXPECT_DOUBLE_EQ(1.0, metersPerUnitVal);
82+
83+
// Check that world prim exists, and that things like physics information
84+
// were parsed correctly
85+
auto worldPrim = this->stage->GetPrimAtPath(pxr::SdfPath(worldPath));
86+
ASSERT_TRUE(worldPrim);
87+
auto physicsScene = pxr::UsdPhysicsScene::Get(this->stage,
88+
pxr::SdfPath(worldPath + "/physics"));
89+
ASSERT_TRUE(physicsScene);
90+
pxr::GfVec3f gravityDirectionVal;
91+
EXPECT_TRUE(physicsScene.GetGravityDirectionAttr().Get(&gravityDirectionVal));
92+
EXPECT_EQ(gravityDirectionVal, pxr::GfVec3f(0, 0, -1));
93+
float gravityMagnitudeVal;
94+
EXPECT_TRUE(physicsScene.GetGravityMagnitudeAttr().Get(&gravityMagnitudeVal));
95+
EXPECT_FLOAT_EQ(gravityMagnitudeVal, 9.8f);
96+
}

usd/src/sdf_parser/sdf2usd_TEST.cc

+97
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,97 @@
1+
/*
2+
* Copyright (C) 2022 Open Source Robotics Foundation
3+
*
4+
* Licensed under the Apache License, Version 2.0 (the "License");
5+
* you may not use this file except in compliance with the License.
6+
* You may obtain a copy of the License at
7+
*
8+
* http://www.apache.org/licenses/LICENSE-2.0
9+
*
10+
* Unless required by applicable law or agreed to in writing, software
11+
* distributed under the License is distributed on an "AS IS" BASIS,
12+
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13+
* See the License for the specific language governing permissions and
14+
* limitations under the License.
15+
*
16+
*/
17+
#include <string>
18+
19+
#include <gtest/gtest.h>
20+
21+
#include <ignition/common/Filesystem.hh>
22+
#include <ignition/common/TempDirectory.hh>
23+
#include <ignition/utilities/ExtraTestMacros.hh>
24+
25+
#include "test_config.h"
26+
#include "test_utils.hh"
27+
28+
#ifdef _WIN32
29+
#define popen _popen
30+
#define pclose _pclose
31+
#endif
32+
33+
static std::string sdf2usdCommand()
34+
{
35+
return ignition::common::joinPaths(std::string(PROJECT_BINARY_DIR), "bin",
36+
"sdf2usd");
37+
}
38+
39+
/////////////////////////////////////////////////
40+
std::string custom_exec_str(std::string _cmd)
41+
{
42+
_cmd += " 2>&1";
43+
FILE *pipe = popen(_cmd.c_str(), "r");
44+
45+
if (!pipe)
46+
return "ERROR";
47+
48+
char buffer[128];
49+
std::string result = "";
50+
51+
while (!feof(pipe))
52+
{
53+
if (fgets(buffer, 128, pipe) != NULL)
54+
result += buffer;
55+
}
56+
57+
pclose(pipe);
58+
return result;
59+
}
60+
61+
/////////////////////////////////////////////////
62+
TEST(check_cmd, IGN_UTILS_TEST_DISABLED_ON_WIN32(SDF))
63+
{
64+
std::string pathBase = PROJECT_SOURCE_PATH;
65+
pathBase = ignition::common::joinPaths(pathBase, "test", "sdf");
66+
67+
auto tmpDir = ignition::common::tempDirectoryPath();
68+
auto tmp = ignition::common::createTempDirectory("usd", tmpDir);
69+
// Check a good SDF file
70+
{
71+
std::string path = ignition::common::joinPaths(pathBase,
72+
"shapes_world.sdf");
73+
const auto outputUsdFilePath =
74+
ignition::common::joinPaths(tmp, "shapes.usd");
75+
EXPECT_FALSE(ignition::common::isFile(outputUsdFilePath));
76+
std::string output =
77+
custom_exec_str(sdf2usdCommand() + " " + path + " " + outputUsdFilePath);
78+
// TODO(adlarkin) make sure 'output' (i.e., the result of running the
79+
// sdf2usd executable) is an empty string once the usd2sdf parser is fully
80+
// implemented (right now, running the parser outputs an error indicating
81+
// that functionality isn't complete)
82+
83+
// make sure that a shapes.usd file was generated
84+
EXPECT_TRUE(ignition::common::isFile(outputUsdFilePath));
85+
86+
// TODO(ahcorde): Check the contents of outputUsdFilePath when the parser
87+
// is implemented
88+
}
89+
}
90+
91+
/////////////////////////////////////////////////
92+
/// Main
93+
int main(int argc, char **argv)
94+
{
95+
::testing::InitGoogleTest(&argc, argv);
96+
return RUN_ALL_TESTS();
97+
}

0 commit comments

Comments
 (0)