From 5e13b49f68e3681ea6ded9f6872424ca54de6d24 Mon Sep 17 00:00:00 2001
From: Ashton Larkin <42042756+adlarkin@users.noreply.github.com>
Date: Thu, 6 Jan 2022 16:56:49 -0700
Subject: [PATCH 01/24] make SDF to USD a separate component of sdformat
Signed-off-by: Ashton Larkin <42042756+adlarkin@users.noreply.github.com>
---
CMakeLists.txt | 11 +-
examples/usdConverter/README.md | 30 ++++
examples/usdConverter/shapes.sdf | 244 +++++++++++++++++++++++++++++
usd/include/CMakeLists.txt | 1 +
usd/include/sdf/CMakeLists.txt | 1 +
usd/include/sdf/usd/CMakeLists.txt | 1 +
usd/include/sdf/usd/World.hh | 42 +++++
usd/src/CMakeLists.txt | 22 +++
usd/src/World.cc | 43 +++++
usd/src/cmd/CMakeLists.txt | 20 +++
usd/src/cmd/sdf2usd.cc | 123 +++++++++++++++
11 files changed, 537 insertions(+), 1 deletion(-)
create mode 100644 examples/usdConverter/README.md
create mode 100644 examples/usdConverter/shapes.sdf
create mode 100644 usd/include/CMakeLists.txt
create mode 100644 usd/include/sdf/CMakeLists.txt
create mode 100644 usd/include/sdf/usd/CMakeLists.txt
create mode 100644 usd/include/sdf/usd/World.hh
create mode 100644 usd/src/CMakeLists.txt
create mode 100644 usd/src/World.cc
create mode 100644 usd/src/cmd/CMakeLists.txt
create mode 100644 usd/src/cmd/sdf2usd.cc
diff --git a/CMakeLists.txt b/CMakeLists.txt
index 5ff7e0038..0f150351c 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -109,8 +109,17 @@ if (BUILD_SDF)
ign_find_package(ignition-utils1 VERSION REQUIRED)
set(IGN_UTILS_VER ${ignition-utils1_VERSION_MAJOR})
+ ########################################
+ # Find ignition common
+ ign_find_package(ignition-common4 COMPONENTS graphics REQUIRED_BY usd)
+ set(IGN_COMMON_VER ${ignition-common4_VERSION_MAJOR})
+
+ ########################################
+ # Find PXR
+ ign_find_package(pxr REQUIRED_BY usd PKGCONFIG pxr)
- ign_configure_build(HIDE_SYMBOLS_BY_DEFAULT QUIT_IF_BUILD_ERRORS)
+ ign_configure_build(HIDE_SYMBOLS_BY_DEFAULT QUIT_IF_BUILD_ERRORS
+ COMPONENTS usd)
ign_create_packages()
add_subdirectory(sdf)
diff --git a/examples/usdConverter/README.md b/examples/usdConverter/README.md
new file mode 100644
index 000000000..323fea82c
--- /dev/null
+++ b/examples/usdConverter/README.md
@@ -0,0 +1,30 @@
+# Converting between SDF and USD
+
+This example shows how a world in a SDF file can be converted to [USD](https://graphics.pixar.com/usd/release/index.html).
+
+## Requirements
+
+You will need all of the dependencies for sdformat, along with the following additional dependencies:
+* USD: [installation instructions](https://github.com/PixarAnimationStudios/USD/blob/release/README.md#getting-and-building-the-code)
+* [ignition-common4](https://github.com/ignitionrobotics/ign-common)
+
+## Setup
+
+Build sdformat, and then run the following commands to build the example (run these commands from this example directory):
+```bash
+mkdir build
+cd build
+cmake ..
+make
+```
+
+You should now have an executable named `sdf2usd`, which can be used to convert a SDF world file to a USD file.
+The following command converts the example `shapes.sdf` file to its USD representation, stored in a file called `shapes.usda` (run this command from the `build` directory):
+```bash
+./sdf2usd ../shapes.sdf shapes.usda
+```
+
+You can now view the contents of the generated USD file with `usdview` (this should have been installed when setting up the USD dependency):
+```
+usdview shapes.usda
+```
diff --git a/examples/usdConverter/shapes.sdf b/examples/usdConverter/shapes.sdf
new file mode 100644
index 000000000..6935ae5d3
--- /dev/null
+++ b/examples/usdConverter/shapes.sdf
@@ -0,0 +1,244 @@
+
+
+
+
+
+ 1.0 1.0 1.0
+ 0.8 0.8 0.8
+
+
+
+ true
+ 0 0 10 0 0 0
+ 0.8 0.8 0.8 1
+ 0.2 0.2 0.2 1
+
+ 1000
+ 0.9
+ 0.01
+ 0.001
+
+ -0.5 0.1 -0.9
+
+
+
+ true
+
+
+
+
+ 0 0 1
+ 100 100
+
+
+
+
+
+
+ 0 0 1
+ 100 100
+
+
+
+ 0.8 0.8 0.8 1
+ 0.8 0.8 0.8 1
+ 0.8 0.8 0.8 1
+
+
+
+
+
+
+ 0 0 0.5 0 0 0
+
+
+
+ 0.16666
+ 0
+ 0
+ 0.16666
+ 0
+ 0.16666
+
+ 1.0
+
+
+
+
+ 1 1 1
+
+
+
+
+
+
+
+ 1 1 1
+
+
+
+ 1 0 0 1
+ 1 0 0 1
+ 1 0 0 1
+
+
+
+
+
+
+ 0 -1.5 0.5 0 0 0
+
+
+
+ 0.1458
+ 0
+ 0
+ 0.1458
+ 0
+ 0.125
+
+ 1.0
+
+
+
+
+ 0.5
+ 1.0
+
+
+
+
+
+
+
+ 0.5
+ 1.0
+
+
+
+ 0 1 0 1
+ 0 1 0 1
+ 0 1 0 1
+
+
+
+
+
+
+ 0 1.5 0.5 0 0 0
+
+
+
+ 0.1
+ 0
+ 0
+ 0.1
+ 0
+ 0.1
+
+ 1.0
+
+
+
+
+ 0.5
+
+
+
+
+
+
+
+ 0.5
+
+
+
+ 0 0 1 1
+ 0 0 1 1
+ 0 0 1 1
+
+
+
+
+
+
+ 0 -3.0 0.5 0 0 0
+
+
+
+ 0.074154
+ 0
+ 0
+ 0.074154
+ 0
+ 0.018769
+
+ 1.0
+
+
+
+
+ 0.2
+ 0.6
+
+
+
+
+
+
+ 0.2
+ 0.6
+
+
+
+ 1 1 0 1
+ 1 1 0 1
+ 1 1 0 1
+
+
+
+
+
+
+ 0 3.0 0.5 0 0 0
+
+
+
+ 0.068
+ 0
+ 0
+ 0.058
+ 0
+ 0.026
+
+ 1.0
+
+
+
+
+ 0.2 0.3 0.5
+
+
+
+
+
+
+ 0.2 0.3 0.5
+
+
+
+ 1 0 1 1
+ 1 0 1 1
+ 1 0 1 1
+
+
+
+
+
+
diff --git a/usd/include/CMakeLists.txt b/usd/include/CMakeLists.txt
new file mode 100644
index 000000000..f2909dd9d
--- /dev/null
+++ b/usd/include/CMakeLists.txt
@@ -0,0 +1 @@
+ign_install_all_headers(COMPONENT usd)
diff --git a/usd/include/sdf/CMakeLists.txt b/usd/include/sdf/CMakeLists.txt
new file mode 100644
index 000000000..f2909dd9d
--- /dev/null
+++ b/usd/include/sdf/CMakeLists.txt
@@ -0,0 +1 @@
+ign_install_all_headers(COMPONENT usd)
diff --git a/usd/include/sdf/usd/CMakeLists.txt b/usd/include/sdf/usd/CMakeLists.txt
new file mode 100644
index 000000000..f2909dd9d
--- /dev/null
+++ b/usd/include/sdf/usd/CMakeLists.txt
@@ -0,0 +1 @@
+ign_install_all_headers(COMPONENT usd)
diff --git a/usd/include/sdf/usd/World.hh b/usd/include/sdf/usd/World.hh
new file mode 100644
index 000000000..7bc763551
--- /dev/null
+++ b/usd/include/sdf/usd/World.hh
@@ -0,0 +1,42 @@
+/*
+ * Copyright (C) 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.
+ *
+*/
+
+#ifndef SDF_USD_WORLD_HH_
+#define SDF_USD_WORLD_HH_
+
+#include
+
+#include
+
+#include "sdf/World.hh"
+#include "sdf/sdf_config.h"
+
+namespace usd
+{
+ /// \brief Parse an SDF world into a USD stage.
+ /// \param[in] _world The SDF world to parse.
+ /// \param[in] _stage The stage that should contain the USD representation
+ /// of _world.
+ /// \param[in] _path The USD path of the parsed world in _stage, which must be
+ /// a valid USD path.
+ /// \return True if _world was succesfully parsed into _stage with a path of
+ /// _path. False otherwise.
+ bool SDFORMAT_VISIBLE ParseSdfWorld(const sdf::World &_world,
+ pxr::UsdStageRefPtr &_stage, const std::string &_path);
+}
+
+#endif
diff --git a/usd/src/CMakeLists.txt b/usd/src/CMakeLists.txt
new file mode 100644
index 000000000..b447ccd8a
--- /dev/null
+++ b/usd/src/CMakeLists.txt
@@ -0,0 +1,22 @@
+# Collect source files into the "sources" variable and unit test files into the
+# "gtest_sources" variable.
+ign_get_libsources_and_unittests(sources gtest_sources)
+
+ign_add_component(usd SOURCES ${sources} GET_TARGET_NAME usd_target)
+
+target_include_directories(${usd_target}
+ PUBLIC
+ ${PXR_INCLUDE_DIRS}
+)
+
+target_link_libraries(${usd_target}
+ PUBLIC
+ ignition-common${IGN_COMMON_VER}::ignition-common${IGN_COMMON_VER}
+ ignition-common${IGN_COMMON_VER}::graphics
+ ${PXR_LIBRARIES}
+)
+
+# Build the unit tests
+ign_build_tests(TYPE UNIT SOURCES ${gtest_sources} LIB_DEPS ${usd_target})
+
+add_subdirectory(cmd)
diff --git a/usd/src/World.cc b/usd/src/World.cc
new file mode 100644
index 000000000..2f56bf442
--- /dev/null
+++ b/usd/src/World.cc
@@ -0,0 +1,43 @@
+/*
+ * Copyright (C) 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 "sdf/usd/World.hh"
+
+#include
+#include
+
+#include
+#include
+#include
+
+namespace usd
+{
+ bool ParseSdfWorld(const sdf::World &_world, pxr::UsdStageRefPtr &_stage,
+ const std::string &_path)
+ {
+ _stage->SetMetadata(pxr::UsdGeomTokens->upAxis, pxr::UsdGeomTokens->z);
+ _stage->SetEndTimeCode(100);
+ _stage->SetMetadata(pxr::TfToken("metersPerUnit"), 1.0);
+ _stage->SetStartTimeCode(0);
+ _stage->SetTimeCodesPerSecond(24);
+
+ // TODO(ahcorde) Add parser
+ std::cerr << "Parser is not yet implemented" << '\n';
+
+ return true;
+ }
+}
diff --git a/usd/src/cmd/CMakeLists.txt b/usd/src/cmd/CMakeLists.txt
new file mode 100644
index 000000000..3fa27abc5
--- /dev/null
+++ b/usd/src/cmd/CMakeLists.txt
@@ -0,0 +1,20 @@
+if(TARGET ${usd_target})
+ add_executable(sdf2usd
+ sdf2usd.cc
+ )
+
+ target_link_libraries(sdf2usd
+ PUBLIC
+ ignition-utils${IGN_UTILS_VER}::ignition-utils${IGN_UTILS_VER}
+ ignition-common${IGN_COMMON_VER}::ignition-common${IGN_COMMON_VER}
+ ignition-common${IGN_COMMON_VER}::graphics
+ ${usd_target}
+ )
+
+ install(
+ TARGETS
+ sdf2usd
+ DESTINATION
+ ${BIN_INSTALL_DIR}
+ )
+endif()
diff --git a/usd/src/cmd/sdf2usd.cc b/usd/src/cmd/sdf2usd.cc
new file mode 100644
index 000000000..ab2be27ed
--- /dev/null
+++ b/usd/src/cmd/sdf2usd.cc
@@ -0,0 +1,123 @@
+/*
+ * Copyright (C) 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
+
+#include
+#include
+
+#include "sdf/sdf.hh"
+#include "sdf/usd/World.hh"
+
+//////////////////////////////////////////////////
+/// \brief Enumeration of available commands
+enum class Command
+{
+ kNone,
+};
+
+//////////////////////////////////////////////////
+/// \brief Structure to hold all available topic options
+struct Options
+{
+ /// \brief Command to execute
+ Command command{Command::kNone};
+
+ /// \brief input filename
+ std::string inputFilename{"input.sdf"};
+
+ /// \brief output filename
+ std::string outputFilename{"output.sdf"};
+};
+
+void runCommand(const Options &_opt)
+{
+ sdf::Root root;
+ auto errors = root.Load(_opt.inputFilename);
+ if (!errors.empty())
+ {
+ std::cerr << "Errors encountered:\n";
+ for (const auto &e : errors)
+ std::cout << e << "\n";
+ exit(-2);
+ }
+
+ // only support SDF files with exactly 1 world for now
+ if (root.WorldCount() != 1u)
+ {
+ std::cerr << _opt.inputFilename << " does not have exactly 1 world\n";
+ exit(-3);
+ }
+
+ auto world = root.WorldByIndex(0u);
+ if (!world)
+ {
+ std::cerr << "Error retrieving the world from "
+ << _opt.inputFilename << "\n";
+ exit(-4);
+ }
+
+ auto stage = pxr::UsdStage::CreateInMemory();
+
+ const auto worldPath = std::string("/" + world->Name());
+ if (!usd::ParseSdfWorld(*world, stage, worldPath))
+ {
+ std::cerr << "Error parsing world [" << world->Name() << "]\n";
+ exit(-5);
+ }
+
+ if (!stage->GetRootLayer()->Export(_opt.outputFilename))
+ {
+ std::cerr << "Issue saving USD to " << _opt.outputFilename << "\n";
+ exit(-6);
+ }
+}
+
+void addFlags(CLI::App &_app)
+{
+ auto opt = std::make_shared();
+
+ _app.add_option("-i,--input",
+ opt->inputFilename,
+ "Input filename");
+
+ _app.add_option("-o,--output",
+ opt->outputFilename,
+ "Output filename");
+
+ _app.callback([&_app, opt](){
+ runCommand(*opt);
+ });
+}
+
+//////////////////////////////////////////////////
+int main(int argc, char** argv)
+{
+ CLI::App app{"Sdf format converter"};
+
+ app.set_help_all_flag("--help-all", "Show all help");
+
+ app.add_flag_callback("--version", [](){
+ std::cout << strdup(SDF_VERSION_FULL) << std::endl;
+ throw CLI::Success();
+ });
+
+ addFlags(app);
+ CLI11_PARSE(app, argc, argv);
+
+ return 0;
+}
From fa4568b4c553a2575ab9228e9795ce93bc18bb57 Mon Sep 17 00:00:00 2001
From: ahcorde
Date: Fri, 7 Jan 2022 12:55:31 +0100
Subject: [PATCH 02/24] Added ignition-common4 as a dependency
Signed-off-by: ahcorde
---
.github/ci/packages.apt | 1 +
1 file changed, 1 insertion(+)
diff --git a/.github/ci/packages.apt b/.github/ci/packages.apt
index 2ea67b09f..4107d6953 100644
--- a/.github/ci/packages.apt
+++ b/.github/ci/packages.apt
@@ -1,3 +1,4 @@
+libignition-common4-dev
libignition-cmake2-dev
libignition-math6-dev
libignition-tools-dev
From 3443bbb406bdd15c93f87a726b65dff3a12d2fbd Mon Sep 17 00:00:00 2001
From: Ashton Larkin <42042756+adlarkin@users.noreply.github.com>
Date: Fri, 7 Jan 2022 19:10:01 -0700
Subject: [PATCH 03/24] add light converting code to usd component
Signed-off-by: Ashton Larkin <42042756+adlarkin@users.noreply.github.com>
---
usd/include/sdf/usd/Light.hh | 42 +++++++
usd/include/sdf/usd/Utils.hh | 119 ++++++++++++++++++
usd/src/CMakeLists.txt | 1 +
usd/src/Light.cc | 126 +++++++++++++++++++
usd/src/Light_Sdf2Usd_TEST.cc | 221 ++++++++++++++++++++++++++++++++++
usd/src/World.cc | 13 ++
6 files changed, 522 insertions(+)
create mode 100644 usd/include/sdf/usd/Light.hh
create mode 100644 usd/include/sdf/usd/Utils.hh
create mode 100644 usd/src/Light.cc
create mode 100644 usd/src/Light_Sdf2Usd_TEST.cc
diff --git a/usd/include/sdf/usd/Light.hh b/usd/include/sdf/usd/Light.hh
new file mode 100644
index 000000000..2e8aab283
--- /dev/null
+++ b/usd/include/sdf/usd/Light.hh
@@ -0,0 +1,42 @@
+/*
+ * Copyright (C) 2021 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 SDF_USD_LIGHT_HH_
+#define SDF_USD_LIGHT_HH_
+
+#include
+
+#include
+
+#include "sdf/Light.hh"
+#include "sdf/sdf_config.h"
+
+namespace usd
+{
+ /// \brief Parse an SDF light into a USD stage.
+ /// \param[in] _light The SDF light to parse.
+ /// \param[in] _stage The stage that should contain the USD representation
+ /// of _light.
+ /// \param[in] _path The USD path of the parsed light in _stage, which must be
+ /// a valid USD path.
+ /// \return True if _light was succesfully parsed into _stage with a path of
+ /// _path. False otherwise.
+ bool SDFORMAT_VISIBLE ParseSdfLight(const sdf::Light &_light,
+ pxr::UsdStageRefPtr &_stage, const std::string &_path);
+}
+
+#endif
diff --git a/usd/include/sdf/usd/Utils.hh b/usd/include/sdf/usd/Utils.hh
new file mode 100644
index 000000000..25bcf4b7d
--- /dev/null
+++ b/usd/include/sdf/usd/Utils.hh
@@ -0,0 +1,119 @@
+/*
+ * Copyright (C) 2021 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 SDF_USD_UTILS_HH_
+#define SDF_USD_UTILS_HH_
+
+#include
+#include
+
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+
+#include "sdf/Geometry.hh"
+#include "sdf/Link.hh"
+#include "sdf/Model.hh"
+#include "sdf/SemanticPose.hh"
+#include "sdf/Visual.hh"
+#include "sdf/sdf_config.h"
+
+namespace usd
+{
+ /// \brief Get an object's pose w.r.t. its parent.
+ /// \param[in] _obj The object whose pose should be computed/retrieved.
+ /// \tparam T An object that has the following method signatures:
+ /// sdf::SemanticPose SemanticPose();
+ /// std::string Name();
+ /// \return _obj's pose w.r.t. its parent. If there was an error computing
+ /// this pose, the pose's position will be NaNs.
+ template
+ inline ignition::math::Pose3d PoseWrtParent(const T &_obj)
+ {
+ ignition::math::Pose3d pose(ignition::math::Vector3d::NaN,
+ ignition::math::Quaterniond::Identity);
+ auto errors = _obj.SemanticPose().Resolve(pose, "");
+ if (!errors.empty())
+ {
+ std::cerr << "Errors occurred when resolving the pose of ["
+ << _obj.Name() << "] w.r.t its parent:\n\t" << errors;
+ }
+ return pose;
+ }
+
+ inline std::string removeDash(const std::string &_str)
+ {
+ std::string result = _str;
+ std::replace(result.begin(), result.end(), '-', '_');
+ return result;
+ }
+
+ /// \brief Set the pose of a pxr::UsdGeomXform object.
+ /// \param[in] _pose The pose to set.
+ /// \param[in] _stage The stage that contains the USD prim at path _usdPath.
+ /// \param[in] _usdPath The path to the USD prim that should have its
+ /// pose modified to match _pose.
+ inline void SDFORMAT_VISIBLE SetPose(const ignition::math::Pose3d &_pose,
+ pxr::UsdStageRefPtr &_stage, const pxr::SdfPath &_usdPath)
+ {
+ pxr::UsdGeomXformCommonAPI geomXformAPI(_stage->GetPrimAtPath(_usdPath));
+
+ const auto &position = _pose.Pos();
+ geomXformAPI.SetTranslate(pxr::GfVec3d(
+ position.X(), position.Y(), position.Z()));
+
+ const auto &rotation = _pose.Rot();
+ // roll/pitch/yaw from ignition::math::Pose3d are in radians, but this API
+ // call expects degrees
+ geomXformAPI.SetRotate(pxr::GfVec3f(
+ ignition::math::Angle(rotation.Roll()).Degree(),
+ ignition::math::Angle(rotation.Pitch()).Degree(),
+ ignition::math::Angle(rotation.Yaw()).Degree()));
+ }
+
+ /// \brief Thickness of an sdf plane
+ /// \note This will no longer be needed when a pxr::USDGeomPlane class
+ /// is created (see the notes in the usd::ParseSdfPlaneGeometry method in
+ /// the geometry.cc file for more information)
+ static const double kPlaneThickness = 0.25;
+
+ /// \brief Check if an sdf model is a plane.
+ /// \param[in] _model The sdf model to check
+ /// \return True if _model is a plane. False otherwise
+ /// \note This method will no longer be needed when a pxr::USDGeomPlane class
+ /// is created (see the notes in the usd::ParseSdfPlaneGeometry method in
+ /// the geometry.cc file for more information)
+ inline bool SDFORMAT_VISIBLE IsPlane(const sdf::Model &_model)
+ {
+ if (_model.LinkCount() != 1u)
+ return false;
+
+ const auto &link = _model.LinkByIndex(0u);
+ if (link->VisualCount() != 1u)
+ return false;
+
+ const auto &visual = link->VisualByIndex(0u);
+ return visual->Geom()->Type() == sdf::GeometryType::PLANE;
+ }
+}
+
+#endif
diff --git a/usd/src/CMakeLists.txt b/usd/src/CMakeLists.txt
index b447ccd8a..2d130b1b2 100644
--- a/usd/src/CMakeLists.txt
+++ b/usd/src/CMakeLists.txt
@@ -17,6 +17,7 @@ target_link_libraries(${usd_target}
)
# Build the unit tests
+include_directories(${PROJECT_SOURCE_DIR}/test)
ign_build_tests(TYPE UNIT SOURCES ${gtest_sources} LIB_DEPS ${usd_target})
add_subdirectory(cmd)
diff --git a/usd/src/Light.cc b/usd/src/Light.cc
new file mode 100644
index 000000000..63b060a2e
--- /dev/null
+++ b/usd/src/Light.cc
@@ -0,0 +1,126 @@
+/*
+ * Copyright (C) 2021 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 "sdf/usd/Light.hh"
+
+#include
+
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+
+#include "sdf/Light.hh"
+#include "sdf/usd/Utils.hh"
+
+namespace usd
+{
+ bool ParseSdfPointLight(const sdf::Light &_light, pxr::UsdStageRefPtr &_stage,
+ const pxr::SdfPath &_path)
+ {
+ auto pointLight = pxr::UsdLuxSphereLight::Define(_stage, _path);
+ pointLight.CreateTreatAsPointAttr().Set(true);
+
+ return true;
+ }
+
+ bool ParseSdfSpotLight(const sdf::Light &_light, pxr::UsdStageRefPtr &_stage,
+ const pxr::SdfPath &_path)
+ {
+ // It may be more realistic to create a cone geometry with its opening pointing
+ // downard, and apply a UsdLuxLightAPI to this geometry. This may gave the
+ // "light emitting from a cone" effect (UsdLuxDiskLight is like light being
+ // emitted from a circular end of a cylinder)
+ pxr::UsdLuxDiskLight::Define(_stage, _path);
+
+ return true;
+ }
+
+ bool ParseSdfDirectionalLight(const sdf::Light &_light,
+ pxr::UsdStageRefPtr &_stage, const pxr::SdfPath &_path)
+ {
+ auto directionalLight = pxr::UsdLuxDistantLight::Define(_stage, _path);
+ directionalLight.CreateIntensityAttr().Set(1000.0f);
+
+ return true;
+ }
+
+ bool ParseSdfLight(const sdf::Light &_light, pxr::UsdStageRefPtr &_stage,
+ const std::string &_path)
+ {
+ const pxr::SdfPath sdfLightPath(_path);
+ bool typeParsed = false;
+ switch (_light.Type())
+ {
+ case sdf::LightType::POINT:
+ typeParsed = ParseSdfPointLight(_light, _stage, sdfLightPath);
+ break;
+ case sdf::LightType::SPOT:
+ typeParsed = ParseSdfSpotLight(_light, _stage, sdfLightPath);
+ break;
+ case sdf::LightType::DIRECTIONAL:
+ // Directional lights in USD have their own intensity attribute
+ // (along with the intensity from the base light class), which is high
+ // to approximate the sun. So, intensity for directional lights
+ // don't need to be increased any further
+ typeParsed = ParseSdfDirectionalLight(_light, _stage, sdfLightPath);
+ break;
+ case sdf::LightType::INVALID:
+ default:
+ std::cerr << "Light type is either invalid or not supported\n";
+ }
+
+ if (typeParsed)
+ {
+ // TODO(adlarkin) figure out how an SDF light's effects the USD
+ // light's pose. For example, a USD directional light with no rotation shines
+ // a light in the -Z direction. So, does an SDF light's need to
+ // be applied to a USD light somehow to ensure the light shines in the
+ // appropriate direction? It seems like orientation of the pose of the SDF
+ // light itself should be ignored, and direction should be used instead to
+ // properly orient the USD light ... maybe I can take the vector,
+ // turn it into a unit vector, extract RPY angle from that somehow, and use
+ // that as the orientation of the light's pose (I'd probably need to flip the
+ // z axis of the direction vector before applying computations on it though,
+ // since USD has lights pointing in -Z by default)
+ usd::SetPose(usd::PoseWrtParent(_light), _stage, sdfLightPath);
+
+
+ // This is a workaround to set the light's intensity attribute. Using the
+ // UsdLuxLightAPI sets the light's inputs:intensity attribute, but isaac
+ // sim reads the light's intensity attribute
+ auto lightPrim = _stage->GetPrimAtPath(sdfLightPath);
+ lightPrim.CreateAttribute(pxr::TfToken("intensity"),
+ pxr::SdfValueTypeNames->Float, false).Set(
+ static_cast(_light.Intensity()) * 100.0f);
+
+ // TODO(adlarkin) Other things to look at (there may be more):
+ // * exposure - I don't think SDF has this, but USD does
+ // (might be worth setting to 1 beause I think intensity is multiplied by
+ // this. See GetExposureAttr() docs for UsdLightAPI class)
+ // * diffuse, specular - USD takes it as a scalar multiplier,
+ // SDF takes it as a RGB color vector
+ // I think the things listed above can be handled by applying a material to the light
+ }
+
+ return typeParsed;
+ }
+}
diff --git a/usd/src/Light_Sdf2Usd_TEST.cc b/usd/src/Light_Sdf2Usd_TEST.cc
new file mode 100644
index 000000000..f1c335973
--- /dev/null
+++ b/usd/src/Light_Sdf2Usd_TEST.cc
@@ -0,0 +1,221 @@
+/*
+ * Copyright 2021 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
+#include
+
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+
+#include "sdf/Light.hh"
+#include "sdf/Root.hh"
+#include "sdf/World.hh"
+#include "sdf/usd/Light.hh"
+#include "sdf/usd/Utils.hh"
+#include "test_config.h"
+
+/////////////////////////////////////////////////
+// Fixture that creates a USD stage for each test case.
+// This fixture also has helper methods to assist with comparing SDF/USD values
+class UsdStageFixture : public ::testing::Test
+{
+ public: UsdStageFixture() = default;
+
+ /// \brief Load an SDF file into the fixture's sdf::Root object
+ /// \param[in] _fileName The name of the file to load
+ /// \return True if _fileName was successfully loaded. False otherwise
+ public: bool LoadSdfFile(const std::string &_fileName)
+ {
+ auto errors = this->root.Load(_fileName);
+ if (!errors.empty())
+ {
+ std::cerr << "Errors encountered:\n";
+ for (const auto &e : errors)
+ std::cout << e << "\n";
+ return false;
+ }
+
+ return true;
+ }
+
+ /// \brief Compare the intensity between a USD and SDF light
+ /// \param[in] _lightPrim The USD light prim
+ /// \param[in] _sdfLight The SDF light
+ public: void CheckLightIntensity(const pxr::UsdPrim &_lightPrim,
+ const sdf::Light &_sdfLight)
+ {
+ bool checkedIntensity = false;
+ if (auto intensityAttr = _lightPrim.GetAttribute(pxr::TfToken("intensity")))
+ {
+ float intensityVal = 0.0;
+ intensityAttr.Get(&intensityVal);
+ EXPECT_FLOAT_EQ(intensityVal, _sdfLight.Intensity() * 10000.0f);
+ checkedIntensity = true;
+ }
+ EXPECT_TRUE(checkedIntensity);
+ }
+
+ /// \brief Compare the pose of a USD prim to a desired pose
+ /// \param[in] _usdPrim The USD prim
+ /// \param[in] _targetPose The pose that _usdPrim should have
+ public: void CheckPrimPose(const pxr::UsdPrim &_usdPrim,
+ const ignition::math::Pose3d &_targetPose)
+ {
+ bool checkedTranslate = false;
+ if (auto translateAttr = _usdPrim.GetAttribute(pxr::TfToken("xformOp:translate")))
+ {
+ pxr::GfVec3d usdTranslation;
+ translateAttr.Get(&usdTranslation);
+ EXPECT_DOUBLE_EQ(usdTranslation[0], _targetPose.Pos().X());
+ EXPECT_DOUBLE_EQ(usdTranslation[1], _targetPose.Pos().Y());
+ EXPECT_DOUBLE_EQ(usdTranslation[2], _targetPose.Pos().Z());
+ checkedTranslate = true;
+ }
+ EXPECT_TRUE(checkedTranslate);
+
+ bool checkedRotate = false;
+ if (auto rotateAttr = _usdPrim.GetAttribute(pxr::TfToken("xformOp:rotateXYZ")))
+ {
+ pxr::GfVec3f usdRotation;
+ rotateAttr.Get(&usdRotation);
+ // USD uses degrees, but SDF uses radians. USD also uses floats for angles
+ // here, but SDF uses doubles
+ const auto sdfRollAngle = static_cast(
+ ignition::math::Angle(_targetPose.Rot().Roll()).Degree());
+ EXPECT_FLOAT_EQ(usdRotation[0], sdfRollAngle);
+ const auto sdfPitchAngle = static_cast(
+ ignition::math::Angle(_targetPose.Rot().Pitch()).Degree());
+ EXPECT_FLOAT_EQ(usdRotation[1], sdfPitchAngle);
+ const auto sdfYawAngle = static_cast(
+ ignition::math::Angle(_targetPose.Rot().Yaw()).Degree());
+ EXPECT_FLOAT_EQ(usdRotation[2], sdfYawAngle);
+ checkedRotate = true;
+ }
+ EXPECT_TRUE(checkedRotate);
+
+ bool checkedOpOrder = false;
+ if (auto opOrderAttr = _usdPrim.GetAttribute(pxr::TfToken("xformOpOrder")))
+ {
+ pxr::VtArray opNames;
+ opOrderAttr.Get(&opNames);
+ // TODO(adlarkin) update this code to handle things like scale in the opOrder
+ // (checking for scale should be done elsehwere since prims aren't always
+ // scaled, but maybe what I can do here is make sure the opNames size is
+ // at least 2 and then make sure translate occurs before rotate)
+ ASSERT_EQ(2u, opNames.size());
+ EXPECT_EQ(pxr::TfToken("xformOp:translate"), opNames[0]);
+ EXPECT_EQ(pxr::TfToken("xformOp:rotateXYZ"), opNames[1]);
+ checkedOpOrder = true;
+ }
+ EXPECT_TRUE(checkedOpOrder);
+ }
+
+ protected: void SetUp() override
+ {
+ this->stage = pxr::UsdStage::CreateInMemory();
+ }
+
+ public: pxr::UsdStageRefPtr stage;
+ public: sdf::Root root;
+};
+
+/////////////////////////////////////////////////
+TEST_F(UsdStageFixture, Lights)
+{
+ const auto path = sdf::testing::TestFile("sdf", "lights.sdf");
+
+ // load the world in the SDF file
+ ASSERT_TRUE(this->LoadSdfFile(path));
+ ASSERT_EQ(1u, this->root.WorldCount());
+ auto world = this->root.WorldByIndex(0u);
+
+ // convert all lights attached directly to the world to USD
+ std::unordered_map lightPathToSdf;
+ for (unsigned int i = 0; i < world->LightCount(); ++i)
+ {
+ const auto light = *(world->LightByIndex(i));
+ const auto lightPath = std::string("/" + light.Name());
+ lightPathToSdf[lightPath] = light;
+ EXPECT_TRUE(usd::ParseSdfLight(light, this->stage, lightPath));
+ }
+ EXPECT_EQ(world->LightCount(), lightPathToSdf.size());
+
+ // check that the lights were parsed correctly
+ int numPointLights = 0;
+ int numSpotLights = 0;
+ int numDirectionalLights = 0;
+ for (const auto &prim : this->stage->Traverse())
+ {
+ auto iter = lightPathToSdf.find(prim.GetPath().GetString());
+ ASSERT_NE(lightPathToSdf.end(), iter);
+ const auto lightUsd = this->stage->GetPrimAtPath(pxr::SdfPath(iter->first));
+ const auto lightSdf = iter->second;
+
+ bool validLight = true;
+ if (lightUsd.IsA())
+ {
+ numPointLights++;
+ this->CheckLightIntensity(lightUsd, lightSdf);
+
+ bool checkedPointAttr = false;
+ if (auto pointAttr = lightUsd.GetAttribute(pxr::TfToken("treatAsPoint")))
+ {
+ bool isPoint = false;
+ pointAttr.Get(&isPoint);
+ EXPECT_TRUE(isPoint);
+ checkedPointAttr = true;
+ }
+ EXPECT_TRUE(checkedPointAttr);
+ }
+ else if (lightUsd.IsA())
+ {
+ numSpotLights++;
+ this->CheckLightIntensity(lightUsd, lightSdf);
+ }
+ else if (lightUsd.IsA())
+ {
+ numDirectionalLights++;
+ // the default intensity for pxr::UsdLuxDistantLight is correct,
+ // so we don't need to make a call to this->CheckLightIntensity
+ // here because no custom intensity is being set for directional
+ // lights in USD (see the "increaseIntensity" variable workaround
+ // in src/usd/sdf_usd_parser/light.cc for more information)
+ }
+ else
+ {
+ validLight = false;
+ }
+
+ EXPECT_TRUE(validLight);
+ if (validLight)
+ this->CheckPrimPose(lightUsd, usd::PoseWrtParent(lightSdf));
+ }
+ EXPECT_EQ(1, numPointLights);
+ EXPECT_EQ(1, numSpotLights);
+ EXPECT_EQ(1, numDirectionalLights);
+}
diff --git a/usd/src/World.cc b/usd/src/World.cc
index 2f56bf442..6e4efd4eb 100644
--- a/usd/src/World.cc
+++ b/usd/src/World.cc
@@ -24,6 +24,8 @@
#include
#include
+#include "sdf/usd/Light.hh"
+
namespace usd
{
bool ParseSdfWorld(const sdf::World &_world, pxr::UsdStageRefPtr &_stage,
@@ -35,6 +37,17 @@ namespace usd
_stage->SetStartTimeCode(0);
_stage->SetTimeCodesPerSecond(24);
+ for (uint64_t i = 0; i < _world.LightCount(); ++i)
+ {
+ const auto light = *(_world.LightByIndex(i));
+ const auto lightPath = std::string(_path + "/" + light.Name());
+ if (!ParseSdfLight(light, _stage, lightPath))
+ {
+ std::cerr << "Error parsing light [" << light.Name() << "]\n";
+ return false;
+ }
+ }
+
// TODO(ahcorde) Add parser
std::cerr << "Parser is not yet implemented" << '\n';
From 18f3ac1f062668043c9517be539237c4bd3dff67 Mon Sep 17 00:00:00 2001
From: Ashton Larkin <42042756+adlarkin@users.noreply.github.com>
Date: Mon, 10 Jan 2022 15:11:52 -0700
Subject: [PATCH 04/24] create world prim and add physics information
Signed-off-by: Ashton Larkin <42042756+adlarkin@users.noreply.github.com>
---
usd/src/World.cc | 19 ++++++++++++++++++-
1 file changed, 18 insertions(+), 1 deletion(-)
diff --git a/usd/src/World.cc b/usd/src/World.cc
index 2f56bf442..6dd03ee71 100644
--- a/usd/src/World.cc
+++ b/usd/src/World.cc
@@ -21,8 +21,13 @@
#include
#include
+#include
+#include
#include
#include
+#include
+
+#include "sdf/World.hh"
namespace usd
{
@@ -35,8 +40,20 @@ namespace usd
_stage->SetStartTimeCode(0);
_stage->SetTimeCodesPerSecond(24);
+ const pxr::SdfPath worldPrimPath(_path);
+ auto usdWorldPrim = _stage->DefinePrim(worldPrimPath);
+
+ auto usdPhysics = pxr::UsdPhysicsScene::Define(_stage,
+ pxr::SdfPath(_path + "/physics"));
+ const auto &sdfWorldGravity = _world.Gravity();
+ const auto normalizedGravity = sdfWorldGravity.Normalized();
+ usdPhysics.CreateGravityDirectionAttr().Set(pxr::GfVec3f(
+ normalizedGravity.X(), normalizedGravity.Y(), normalizedGravity.Z()));
+ usdPhysics.CreateGravityMagnitudeAttr().Set(
+ static_cast(sdfWorldGravity.Length()));
+
// TODO(ahcorde) Add parser
- std::cerr << "Parser is not yet implemented" << '\n';
+ std::cerr << "Parser for a sdf world is not yet implemented\n";
return true;
}
From 3bbd6eaf17029e8cd3029fd12ce7477703c16919 Mon Sep 17 00:00:00 2001
From: Ashton Larkin <42042756+adlarkin@users.noreply.github.com>
Date: Mon, 10 Jan 2022 17:34:43 -0700
Subject: [PATCH 05/24] add unit test for world conversion
Signed-off-by: Ashton Larkin <42042756+adlarkin@users.noreply.github.com>
---
test/test_utils.hh | 21 +++++++++
usd/src/CMakeLists.txt | 7 ++-
usd/src/World.cc | 4 +-
usd/src/World_Sdf2Usd_TEST.cc | 87 +++++++++++++++++++++++++++++++++++
4 files changed, 117 insertions(+), 2 deletions(-)
create mode 100644 usd/src/World_Sdf2Usd_TEST.cc
diff --git a/test/test_utils.hh b/test/test_utils.hh
index 150f70b60..e52599dad 100644
--- a/test/test_utils.hh
+++ b/test/test_utils.hh
@@ -18,7 +18,9 @@
#define SDF_TEST_UTILS_HH_
#include
+#include
#include "sdf/Console.hh"
+#include "sdf/Root.hh"
namespace sdf
{
@@ -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
diff --git a/usd/src/CMakeLists.txt b/usd/src/CMakeLists.txt
index b447ccd8a..4b8de3a34 100644
--- a/usd/src/CMakeLists.txt
+++ b/usd/src/CMakeLists.txt
@@ -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)
diff --git a/usd/src/World.cc b/usd/src/World.cc
index 6dd03ee71..e8ae2b2bf 100644
--- a/usd/src/World.cc
+++ b/usd/src/World.cc
@@ -53,7 +53,9 @@ namespace usd
static_cast(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;
}
diff --git a/usd/src/World_Sdf2Usd_TEST.cc b/usd/src/World_Sdf2Usd_TEST.cc
new file mode 100644
index 000000000..2c52c26ad
--- /dev/null
+++ b/usd/src/World_Sdf2Usd_TEST.cc
@@ -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
+
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+
+#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);
+}
From 16e0789bd4c4d56525d06fe273fc865a4c0bc61a Mon Sep 17 00:00:00 2001
From: ahcorde
Date: Tue, 11 Jan 2022 15:33:26 +0100
Subject: [PATCH 06/24] Added ci to compile with USD
Signed-off-by: ahcorde
---
.github/ci/before_cmake.sh | 58 ++++++++++++++++++++++++++++++++++++++
.github/ci/packages.apt | 1 +
.github/workflows/ci.yml | 10 +++++++
3 files changed, 69 insertions(+)
create mode 100644 .github/ci/before_cmake.sh
diff --git a/.github/ci/before_cmake.sh b/.github/ci/before_cmake.sh
new file mode 100644
index 000000000..a0e23f85c
--- /dev/null
+++ b/.github/ci/before_cmake.sh
@@ -0,0 +1,58 @@
+#!/bin/sh -l
+
+set -x
+
+BUILD_DIR=`pwd`
+
+cd /tmp
+
+# check that we can compile USD from sources
+mkdir cmake_test
+cd cmake_test
+
+echo "cmake_minimum_required(VERSION 3.12)" > CMakeLists.txt
+
+return_code=0
+cmake . || return_code=$(($return_code + $?))
+if [ $return_code -eq 0 ]
+then
+ # compile USD from sources
+ cd /tmp
+ mkdir usd_binaries
+ cd usd_binaries
+
+ apt-get install libboost-all-dev libtbb-dev p7zip-full -y
+
+ wget https://github.com/PixarAnimationStudios/USD/archive/refs/tags/v21.11.zip
+ unzip v21.11.zip
+ sed -i '2059 i \ \ \ \ requiredDependencies.remove(BOOST)' USD-21.11/build_scripts/build_usd.py
+ cd USD-21.11
+ mkdir build
+ cd build
+
+ cmake -DCMAKE_INSTALL_PREFIX="/tmp/USD" -DCMAKE_PREFIX_PATH="/tmp/USD" \
+ -DCMAKE_BUILD_TYPE=Release \
+ -DPXR_PREFER_SAFETY_OVER_SPEED=ON \
+ -DPXR_ENABLE_PYTHON_SUPPORT=OFF \
+ -DBUILD_SHARED_LIBS=ON \
+ -DTBB_USE_DEBUG_BUILD=OFF \
+ -DPXR_BUILD_DOCUMENTATION=OFF \
+ -DPXR_BUILD_TESTS=OFF \
+ -DPXR_BUILD_EXAMPLES=OFF \
+ -DPXR_BUILD_TUTORIALS=OFF \
+ -DPXR_BUILD_USD_TOOLS=OFF \
+ -DPXR_BUILD_IMAGING=OFF \
+ -DPXR_BUILD_USD_IMAGING=OFF \
+ -DPXR_BUILD_USDVIEW=OFF \
+ -DPXR_BUILD_ALEMBIC_PLUGIN=OFF \
+ -DPXR_BUILD_DRACO_PLUGIN=OFF \
+ -DPXR_ENABLE_MATERIALX_SUPPORT=OFF \
+ -DBoost_NO_BOOST_CMAKE=On \
+ -DBoost_INCLUDE_DIR=/usr/include \
+ -DBoost_NO_BOOST_CMAKE=FALSE \
+ ..
+
+ make -j$(nproc) install
+fi
+
+cd $BUILD_DIR
diff --git a/.github/ci/packages.apt b/.github/ci/packages.apt
index 4107d6953..e39a4b6eb 100644
--- a/.github/ci/packages.apt
+++ b/.github/ci/packages.apt
@@ -3,6 +3,7 @@ libignition-cmake2-dev
libignition-math6-dev
libignition-tools-dev
libignition-utils1-dev
+libignition-utils1-cli-dev
libtinyxml2-dev
liburdfdom-dev
libxml2-utils
diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml
index 2914eb5d5..613c0531d 100644
--- a/.github/workflows/ci.yml
+++ b/.github/workflows/ci.yml
@@ -7,6 +7,11 @@ jobs:
runs-on: ubuntu-latest
name: Ubuntu Bionic CI
steps:
+ - name: Set env
+ run: |
+ export PATH=$PATH:/tmp/usd_binaries/bin
+ export LD_LIBRARY_PATH=$LD_LIBRARY_PATH:/tmp/usd_binaries/lib
+ export CMAKE_PREFIX_PATH=$CMAKE_PREFIX_PATH:/tmp/usd_binaries
- name: Checkout
uses: actions/checkout@v2
- name: Compile and test
@@ -18,6 +23,11 @@ jobs:
runs-on: ubuntu-latest
name: Ubuntu Focal CI
steps:
+ - name: Set env
+ run: |
+ echo "PATH=$PATH:/tmp/USD/bin" >> $GITHUB_ENV
+ echo "LD_LIBRARY_PATH=$LD_LIBRARY_PATH:/tmp/USD/lib" >> $GITHUB_ENV
+ echo "CMAKE_PREFIX_PATH=$CMAKE_PREFIX_PATH:/tmp/USD" >> $GITHUB_ENV
- name: Checkout
uses: actions/checkout@v2
- name: Compile and test
From 4cdd0549c596cef34df8155c10e3b25f898c1355 Mon Sep 17 00:00:00 2001
From: Ashton Larkin <42042756+adlarkin@users.noreply.github.com>
Date: Tue, 11 Jan 2022 18:37:28 -0700
Subject: [PATCH 07/24] cleanup light code before first review
Signed-off-by: Ashton Larkin <42042756+adlarkin@users.noreply.github.com>
---
usd/include/sdf/usd/Light.hh | 2 +-
usd/include/sdf/usd/Utils.hh | 36 +----------
usd/src/CMakeLists.txt | 4 +-
usd/src/Light.cc | 73 +++++-----------------
usd/src/Light_Sdf2Usd_TEST.cc | 114 ++++++----------------------------
usd/src/UsdTestUtils.hh | 93 +++++++++++++++++++++++++++
6 files changed, 136 insertions(+), 186 deletions(-)
create mode 100644 usd/src/UsdTestUtils.hh
diff --git a/usd/include/sdf/usd/Light.hh b/usd/include/sdf/usd/Light.hh
index 2e8aab283..ffaff51e1 100644
--- a/usd/include/sdf/usd/Light.hh
+++ b/usd/include/sdf/usd/Light.hh
@@ -1,5 +1,5 @@
/*
- * Copyright (C) 2021 Open Source Robotics Foundation
+ * Copyright (C) 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.
diff --git a/usd/include/sdf/usd/Utils.hh b/usd/include/sdf/usd/Utils.hh
index 25bcf4b7d..42a4f4e3c 100644
--- a/usd/include/sdf/usd/Utils.hh
+++ b/usd/include/sdf/usd/Utils.hh
@@ -1,5 +1,5 @@
/*
- * Copyright (C) 2021 Open Source Robotics Foundation
+ * Copyright (C) 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.
@@ -60,14 +60,7 @@ namespace usd
return pose;
}
- inline std::string removeDash(const std::string &_str)
- {
- std::string result = _str;
- std::replace(result.begin(), result.end(), '-', '_');
- return result;
- }
-
- /// \brief Set the pose of a pxr::UsdGeomXform object.
+ /// \brief Set the pose of a USD prim.
/// \param[in] _pose The pose to set.
/// \param[in] _stage The stage that contains the USD prim at path _usdPath.
/// \param[in] _usdPath The path to the USD prim that should have its
@@ -89,31 +82,6 @@ namespace usd
ignition::math::Angle(rotation.Pitch()).Degree(),
ignition::math::Angle(rotation.Yaw()).Degree()));
}
-
- /// \brief Thickness of an sdf plane
- /// \note This will no longer be needed when a pxr::USDGeomPlane class
- /// is created (see the notes in the usd::ParseSdfPlaneGeometry method in
- /// the geometry.cc file for more information)
- static const double kPlaneThickness = 0.25;
-
- /// \brief Check if an sdf model is a plane.
- /// \param[in] _model The sdf model to check
- /// \return True if _model is a plane. False otherwise
- /// \note This method will no longer be needed when a pxr::USDGeomPlane class
- /// is created (see the notes in the usd::ParseSdfPlaneGeometry method in
- /// the geometry.cc file for more information)
- inline bool SDFORMAT_VISIBLE IsPlane(const sdf::Model &_model)
- {
- if (_model.LinkCount() != 1u)
- return false;
-
- const auto &link = _model.LinkByIndex(0u);
- if (link->VisualCount() != 1u)
- return false;
-
- const auto &visual = link->VisualByIndex(0u);
- return visual->Geom()->Type() == sdf::GeometryType::PLANE;
- }
}
#endif
diff --git a/usd/src/CMakeLists.txt b/usd/src/CMakeLists.txt
index 4b8de3a34..9eb335d40 100644
--- a/usd/src/CMakeLists.txt
+++ b/usd/src/CMakeLists.txt
@@ -21,7 +21,9 @@ ign_build_tests(
TYPE UNIT
SOURCES ${gtest_sources}
LIB_DEPS ${usd_target}
- INCLUDE_DIRS ${PROJECT_SOURCE_DIR}/test
+ INCLUDE_DIRS
+ ${CMAKE_CURRENT_SOURCE_DIR}
+ ${PROJECT_SOURCE_DIR}/test
)
add_subdirectory(cmd)
diff --git a/usd/src/Light.cc b/usd/src/Light.cc
index 63b060a2e..a172cb4ef 100644
--- a/usd/src/Light.cc
+++ b/usd/src/Light.cc
@@ -1,5 +1,5 @@
/*
- * Copyright (C) 2021 Open Source Robotics Foundation
+ * Copyright (C) 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.
@@ -33,77 +33,39 @@
namespace usd
{
- bool ParseSdfPointLight(const sdf::Light &_light, pxr::UsdStageRefPtr &_stage,
- const pxr::SdfPath &_path)
- {
- auto pointLight = pxr::UsdLuxSphereLight::Define(_stage, _path);
- pointLight.CreateTreatAsPointAttr().Set(true);
-
- return true;
- }
-
- bool ParseSdfSpotLight(const sdf::Light &_light, pxr::UsdStageRefPtr &_stage,
- const pxr::SdfPath &_path)
- {
- // It may be more realistic to create a cone geometry with its opening pointing
- // downard, and apply a UsdLuxLightAPI to this geometry. This may gave the
- // "light emitting from a cone" effect (UsdLuxDiskLight is like light being
- // emitted from a circular end of a cylinder)
- pxr::UsdLuxDiskLight::Define(_stage, _path);
-
- return true;
- }
-
- bool ParseSdfDirectionalLight(const sdf::Light &_light,
- pxr::UsdStageRefPtr &_stage, const pxr::SdfPath &_path)
- {
- auto directionalLight = pxr::UsdLuxDistantLight::Define(_stage, _path);
- directionalLight.CreateIntensityAttr().Set(1000.0f);
-
- return true;
- }
-
bool ParseSdfLight(const sdf::Light &_light, pxr::UsdStageRefPtr &_stage,
const std::string &_path)
{
const pxr::SdfPath sdfLightPath(_path);
- bool typeParsed = false;
+ bool typeParsed = true;
switch (_light.Type())
{
case sdf::LightType::POINT:
- typeParsed = ParseSdfPointLight(_light, _stage, sdfLightPath);
+ {
+ auto pointLight =
+ pxr::UsdLuxSphereLight::Define(_stage, sdfLightPath);
+ pointLight.CreateTreatAsPointAttr().Set(true);
+ }
break;
case sdf::LightType::SPOT:
- typeParsed = ParseSdfSpotLight(_light, _stage, sdfLightPath);
+ pxr::UsdLuxDiskLight::Define(_stage, sdfLightPath);
break;
case sdf::LightType::DIRECTIONAL:
- // Directional lights in USD have their own intensity attribute
- // (along with the intensity from the base light class), which is high
- // to approximate the sun. So, intensity for directional lights
- // don't need to be increased any further
- typeParsed = ParseSdfDirectionalLight(_light, _stage, sdfLightPath);
+ pxr::UsdLuxDistantLight::Define(_stage, sdfLightPath);
break;
case sdf::LightType::INVALID:
default:
std::cerr << "Light type is either invalid or not supported\n";
+ typeParsed = false;
}
if (typeParsed)
{
- // TODO(adlarkin) figure out how an SDF light's effects the USD
- // light's pose. For example, a USD directional light with no rotation shines
- // a light in the -Z direction. So, does an SDF light's need to
- // be applied to a USD light somehow to ensure the light shines in the
- // appropriate direction? It seems like orientation of the pose of the SDF
- // light itself should be ignored, and direction should be used instead to
- // properly orient the USD light ... maybe I can take the vector,
- // turn it into a unit vector, extract RPY angle from that somehow, and use
- // that as the orientation of the light's pose (I'd probably need to flip the
- // z axis of the direction vector before applying computations on it though,
- // since USD has lights pointing in -Z by default)
+ // TODO(adlarkin) incorporate sdf::Light's somehow? According
+ // to the USD API, things like UsdLuxDistantLight and UsdLuxDiskLight emit
+ // light along the -Z axis, so I'm not sure if this can be changed.
usd::SetPose(usd::PoseWrtParent(_light), _stage, sdfLightPath);
-
// This is a workaround to set the light's intensity attribute. Using the
// UsdLuxLightAPI sets the light's inputs:intensity attribute, but isaac
// sim reads the light's intensity attribute
@@ -113,12 +75,11 @@ namespace usd
static_cast(_light.Intensity()) * 100.0f);
// TODO(adlarkin) Other things to look at (there may be more):
- // * exposure - I don't think SDF has this, but USD does
- // (might be worth setting to 1 beause I think intensity is multiplied by
- // this. See GetExposureAttr() docs for UsdLightAPI class)
+ // * exposure - I don't think SDF has this, but USD does. See the
+ // UsdLightAPI::GetExposureAttr method
// * diffuse, specular - USD takes it as a scalar multiplier,
- // SDF takes it as a RGB color vector
- // I think the things listed above can be handled by applying a material to the light
+ // SDF takes it as a RGB color vector. Perhaps this can be handled by
+ // applying a material to a light
}
return typeParsed;
diff --git a/usd/src/Light_Sdf2Usd_TEST.cc b/usd/src/Light_Sdf2Usd_TEST.cc
index f1c335973..d0ffa117a 100644
--- a/usd/src/Light_Sdf2Usd_TEST.cc
+++ b/usd/src/Light_Sdf2Usd_TEST.cc
@@ -1,5 +1,5 @@
/*
- * Copyright 2021 Open Source Robotics Foundation
+ * 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.
@@ -19,11 +19,7 @@
#include
#include
-#include
#include
-#include
-#include
-#include
#include
#include
#include
@@ -38,30 +34,16 @@
#include "sdf/usd/Light.hh"
#include "sdf/usd/Utils.hh"
#include "test_config.h"
+#include "test_utils.hh"
+#include "UsdTestUtils.hh"
/////////////////////////////////////////////////
// Fixture that creates a USD stage for each test case.
-// This fixture also has helper methods to assist with comparing SDF/USD values
-class UsdStageFixture : public ::testing::Test
+// This fixture also has helper methods to assist with comparing SDF/USD light
+// values
+class UsdLightStageFixture : public ::testing::Test
{
- public: UsdStageFixture() = default;
-
- /// \brief Load an SDF file into the fixture's sdf::Root object
- /// \param[in] _fileName The name of the file to load
- /// \return True if _fileName was successfully loaded. False otherwise
- public: bool LoadSdfFile(const std::string &_fileName)
- {
- auto errors = this->root.Load(_fileName);
- if (!errors.empty())
- {
- std::cerr << "Errors encountered:\n";
- for (const auto &e : errors)
- std::cout << e << "\n";
- return false;
- }
-
- return true;
- }
+ public: UsdLightStageFixture() = default;
/// \brief Compare the intensity between a USD and SDF light
/// \param[in] _lightPrim The USD light prim
@@ -74,87 +56,35 @@ class UsdStageFixture : public ::testing::Test
{
float intensityVal = 0.0;
intensityAttr.Get(&intensityVal);
- EXPECT_FLOAT_EQ(intensityVal, _sdfLight.Intensity() * 10000.0f);
+ EXPECT_FLOAT_EQ(intensityVal, _sdfLight.Intensity() * 100.0f);
checkedIntensity = true;
}
EXPECT_TRUE(checkedIntensity);
}
- /// \brief Compare the pose of a USD prim to a desired pose
- /// \param[in] _usdPrim The USD prim
- /// \param[in] _targetPose The pose that _usdPrim should have
- public: void CheckPrimPose(const pxr::UsdPrim &_usdPrim,
- const ignition::math::Pose3d &_targetPose)
- {
- bool checkedTranslate = false;
- if (auto translateAttr = _usdPrim.GetAttribute(pxr::TfToken("xformOp:translate")))
- {
- pxr::GfVec3d usdTranslation;
- translateAttr.Get(&usdTranslation);
- EXPECT_DOUBLE_EQ(usdTranslation[0], _targetPose.Pos().X());
- EXPECT_DOUBLE_EQ(usdTranslation[1], _targetPose.Pos().Y());
- EXPECT_DOUBLE_EQ(usdTranslation[2], _targetPose.Pos().Z());
- checkedTranslate = true;
- }
- EXPECT_TRUE(checkedTranslate);
-
- bool checkedRotate = false;
- if (auto rotateAttr = _usdPrim.GetAttribute(pxr::TfToken("xformOp:rotateXYZ")))
- {
- pxr::GfVec3f usdRotation;
- rotateAttr.Get(&usdRotation);
- // USD uses degrees, but SDF uses radians. USD also uses floats for angles
- // here, but SDF uses doubles
- const auto sdfRollAngle = static_cast(
- ignition::math::Angle(_targetPose.Rot().Roll()).Degree());
- EXPECT_FLOAT_EQ(usdRotation[0], sdfRollAngle);
- const auto sdfPitchAngle = static_cast(
- ignition::math::Angle(_targetPose.Rot().Pitch()).Degree());
- EXPECT_FLOAT_EQ(usdRotation[1], sdfPitchAngle);
- const auto sdfYawAngle = static_cast(
- ignition::math::Angle(_targetPose.Rot().Yaw()).Degree());
- EXPECT_FLOAT_EQ(usdRotation[2], sdfYawAngle);
- checkedRotate = true;
- }
- EXPECT_TRUE(checkedRotate);
-
- bool checkedOpOrder = false;
- if (auto opOrderAttr = _usdPrim.GetAttribute(pxr::TfToken("xformOpOrder")))
- {
- pxr::VtArray opNames;
- opOrderAttr.Get(&opNames);
- // TODO(adlarkin) update this code to handle things like scale in the opOrder
- // (checking for scale should be done elsehwere since prims aren't always
- // scaled, but maybe what I can do here is make sure the opNames size is
- // at least 2 and then make sure translate occurs before rotate)
- ASSERT_EQ(2u, opNames.size());
- EXPECT_EQ(pxr::TfToken("xformOp:translate"), opNames[0]);
- EXPECT_EQ(pxr::TfToken("xformOp:rotateXYZ"), opNames[1]);
- checkedOpOrder = true;
- }
- EXPECT_TRUE(checkedOpOrder);
- }
-
protected: void SetUp() override
{
this->stage = pxr::UsdStage::CreateInMemory();
+ ASSERT_TRUE(this->stage);
}
public: pxr::UsdStageRefPtr stage;
- public: sdf::Root root;
};
/////////////////////////////////////////////////
-TEST_F(UsdStageFixture, Lights)
+TEST_F(UsdLightStageFixture, Lights)
{
const auto path = sdf::testing::TestFile("sdf", "lights.sdf");
+ sdf::Root root;
// load the world in the SDF file
- ASSERT_TRUE(this->LoadSdfFile(path));
- ASSERT_EQ(1u, this->root.WorldCount());
- auto world = this->root.WorldByIndex(0u);
+ ASSERT_TRUE(sdf::testing::LoadSdfFile(path, root));
+ ASSERT_EQ(1u, root.WorldCount());
+ auto world = root.WorldByIndex(0u);
// convert all lights attached directly to the world to USD
+ // TODO(adlarkin) convert and test lights attached to models once parsing
+ // functionality is added for sdf::Model to USD
std::unordered_map lightPathToSdf;
for (unsigned int i = 0; i < world->LightCount(); ++i)
{
@@ -180,7 +110,6 @@ TEST_F(UsdStageFixture, Lights)
if (lightUsd.IsA())
{
numPointLights++;
- this->CheckLightIntensity(lightUsd, lightSdf);
bool checkedPointAttr = false;
if (auto pointAttr = lightUsd.GetAttribute(pxr::TfToken("treatAsPoint")))
@@ -195,16 +124,10 @@ TEST_F(UsdStageFixture, Lights)
else if (lightUsd.IsA())
{
numSpotLights++;
- this->CheckLightIntensity(lightUsd, lightSdf);
}
else if (lightUsd.IsA())
{
numDirectionalLights++;
- // the default intensity for pxr::UsdLuxDistantLight is correct,
- // so we don't need to make a call to this->CheckLightIntensity
- // here because no custom intensity is being set for directional
- // lights in USD (see the "increaseIntensity" variable workaround
- // in src/usd/sdf_usd_parser/light.cc for more information)
}
else
{
@@ -213,7 +136,10 @@ TEST_F(UsdStageFixture, Lights)
EXPECT_TRUE(validLight);
if (validLight)
- this->CheckPrimPose(lightUsd, usd::PoseWrtParent(lightSdf));
+ {
+ this->CheckLightIntensity(lightUsd, lightSdf);
+ usd::testing::CheckPrimPose(lightUsd, usd::PoseWrtParent(lightSdf));
+ }
}
EXPECT_EQ(1, numPointLights);
EXPECT_EQ(1, numSpotLights);
diff --git a/usd/src/UsdTestUtils.hh b/usd/src/UsdTestUtils.hh
new file mode 100644
index 000000000..6670bb3ce
--- /dev/null
+++ b/usd/src/UsdTestUtils.hh
@@ -0,0 +1,93 @@
+/*
+ * Copyright (C) 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.
+ *
+*/
+#ifndef SDF_USD_TEST_UTILS_HH_
+#define SDF_USD_TEST_UTILS_HH_
+
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+
+namespace usd
+{
+namespace testing
+{
+
+/// \brief Compare the pose of a USD prim to a desired pose
+/// \param[in] _usdPrim The USD prim
+/// \param[in] _targetPose The pose that _usdPrim should have
+void CheckPrimPose(const pxr::UsdPrim &_usdPrim,
+ const ignition::math::Pose3d &_targetPose)
+{
+ bool checkedTranslate = false;
+ if (auto translateAttr =
+ _usdPrim.GetAttribute(pxr::TfToken("xformOp:translate")))
+ {
+ pxr::GfVec3d usdTranslation;
+ translateAttr.Get(&usdTranslation);
+ EXPECT_DOUBLE_EQ(usdTranslation[0], _targetPose.Pos().X());
+ EXPECT_DOUBLE_EQ(usdTranslation[1], _targetPose.Pos().Y());
+ EXPECT_DOUBLE_EQ(usdTranslation[2], _targetPose.Pos().Z());
+ checkedTranslate = true;
+ }
+ EXPECT_TRUE(checkedTranslate);
+
+ bool checkedRotate = false;
+ if (auto rotateAttr =
+ _usdPrim.GetAttribute(pxr::TfToken("xformOp:rotateXYZ")))
+ {
+ pxr::GfVec3f usdRotation;
+ rotateAttr.Get(&usdRotation);
+ // USD uses degrees, but SDF uses radians. USD also uses floats for angles
+ // here, but SDF uses doubles
+ const auto sdfRollAngle = static_cast(
+ ignition::math::Angle(_targetPose.Rot().Roll()).Degree());
+ EXPECT_FLOAT_EQ(usdRotation[0], sdfRollAngle);
+ const auto sdfPitchAngle = static_cast(
+ ignition::math::Angle(_targetPose.Rot().Pitch()).Degree());
+ EXPECT_FLOAT_EQ(usdRotation[1], sdfPitchAngle);
+ const auto sdfYawAngle = static_cast(
+ ignition::math::Angle(_targetPose.Rot().Yaw()).Degree());
+ EXPECT_FLOAT_EQ(usdRotation[2], sdfYawAngle);
+ checkedRotate = true;
+ }
+ EXPECT_TRUE(checkedRotate);
+
+ bool checkedOpOrder = false;
+ if (auto opOrderAttr = _usdPrim.GetAttribute(pxr::TfToken("xformOpOrder")))
+ {
+ pxr::VtArray opNames;
+ opOrderAttr.Get(&opNames);
+ // TODO(adlarkin) handle things like scale in the opOrder
+ // (checking for scale should be done elsehwere since prims aren't always
+ // scaled, but maybe what I can do here is make sure the opNames size is
+ // at least 2 and then make sure translate occurs before rotate)
+ ASSERT_EQ(2u, opNames.size());
+ EXPECT_EQ(pxr::TfToken("xformOp:translate"), opNames[0]);
+ EXPECT_EQ(pxr::TfToken("xformOp:rotateXYZ"), opNames[1]);
+ checkedOpOrder = true;
+ }
+ EXPECT_TRUE(checkedOpOrder);
+}
+
+} // namespace testing
+} // namespace usd
+
+#endif
From b32b0f3b8195b7bb9088043ded1444fc4c5da626 Mon Sep 17 00:00:00 2001
From: Ashton Larkin <42042756+adlarkin@users.noreply.github.com>
Date: Tue, 11 Jan 2022 18:51:42 -0700
Subject: [PATCH 08/24] remove extra includes, add symbol visibility
Signed-off-by: Ashton Larkin <42042756+adlarkin@users.noreply.github.com>
---
usd/include/sdf/usd/Utils.hh | 11 +----------
1 file changed, 1 insertion(+), 10 deletions(-)
diff --git a/usd/include/sdf/usd/Utils.hh b/usd/include/sdf/usd/Utils.hh
index 42a4f4e3c..4a2cf7c72 100644
--- a/usd/include/sdf/usd/Utils.hh
+++ b/usd/include/sdf/usd/Utils.hh
@@ -18,23 +18,15 @@
#ifndef SDF_USD_UTILS_HH_
#define SDF_USD_UTILS_HH_
-#include
-#include
-
#include
#include
#include
#include
#include
-#include
#include
#include
-#include "sdf/Geometry.hh"
-#include "sdf/Link.hh"
-#include "sdf/Model.hh"
#include "sdf/SemanticPose.hh"
-#include "sdf/Visual.hh"
#include "sdf/sdf_config.h"
namespace usd
@@ -43,11 +35,10 @@ namespace usd
/// \param[in] _obj The object whose pose should be computed/retrieved.
/// \tparam T An object that has the following method signatures:
/// sdf::SemanticPose SemanticPose();
- /// std::string Name();
/// \return _obj's pose w.r.t. its parent. If there was an error computing
/// this pose, the pose's position will be NaNs.
template
- inline ignition::math::Pose3d PoseWrtParent(const T &_obj)
+ inline ignition::math::Pose3d SDFORMAT_VISIBLE PoseWrtParent(const T &_obj)
{
ignition::math::Pose3d pose(ignition::math::Vector3d::NaN,
ignition::math::Quaterniond::Identity);
From ae3ee43b017e13bcc09cb671b00cfb3358c28bab Mon Sep 17 00:00:00 2001
From: ahcorde
Date: Mon, 17 Jan 2022 13:26:38 +0100
Subject: [PATCH 09/24] Added feedback
Signed-off-by: ahcorde
---
usd/include/CMakeLists.txt | 2 +-
usd/include/sdf/usd/World.hh | 6 ++++--
usd/src/CMakeLists.txt | 1 -
usd/src/World.cc | 8 ++++++--
usd/src/World_Sdf2Usd_TEST.cc | 6 +++++-
usd/src/cmd/sdf2usd.cc | 8 ++++++--
6 files changed, 22 insertions(+), 9 deletions(-)
diff --git a/usd/include/CMakeLists.txt b/usd/include/CMakeLists.txt
index f2909dd9d..9c28e4b11 100644
--- a/usd/include/CMakeLists.txt
+++ b/usd/include/CMakeLists.txt
@@ -1 +1 @@
-ign_install_all_headers(COMPONENT usd)
+add_subdirectory(sdf/usd)
diff --git a/usd/include/sdf/usd/World.hh b/usd/include/sdf/usd/World.hh
index 7bc763551..605831ad2 100644
--- a/usd/include/sdf/usd/World.hh
+++ b/usd/include/sdf/usd/World.hh
@@ -20,10 +20,12 @@
#include
+#pragma push_macro ("__DEPRECATED")
+#undef __DEPRECATED
#include
+#pragma pop_macro ("__DEPRECATED")
#include "sdf/World.hh"
-#include "sdf/sdf_config.h"
namespace usd
{
@@ -35,7 +37,7 @@ namespace usd
/// a valid USD path.
/// \return True if _world was succesfully parsed into _stage with a path of
/// _path. False otherwise.
- bool SDFORMAT_VISIBLE ParseSdfWorld(const sdf::World &_world,
+ sdf::Errors SDFORMAT_VISIBLE ParseSdfWorld(const sdf::World &_world,
pxr::UsdStageRefPtr &_stage, const std::string &_path);
}
diff --git a/usd/src/CMakeLists.txt b/usd/src/CMakeLists.txt
index 4b8de3a34..e1d24493d 100644
--- a/usd/src/CMakeLists.txt
+++ b/usd/src/CMakeLists.txt
@@ -12,7 +12,6 @@ target_include_directories(${usd_target}
target_link_libraries(${usd_target}
PUBLIC
ignition-common${IGN_COMMON_VER}::ignition-common${IGN_COMMON_VER}
- ignition-common${IGN_COMMON_VER}::graphics
${PXR_LIBRARIES}
)
diff --git a/usd/src/World.cc b/usd/src/World.cc
index e8ae2b2bf..226fb97c9 100644
--- a/usd/src/World.cc
+++ b/usd/src/World.cc
@@ -23,7 +23,10 @@
#include
#include
#include
+#pragma push_macro ("__DEPRECATED")
+#undef __DEPRECATED
#include
+#pragma pop_macro ("__DEPRECATED")
#include
#include
@@ -31,9 +34,10 @@
namespace usd
{
- bool ParseSdfWorld(const sdf::World &_world, pxr::UsdStageRefPtr &_stage,
+ sdf::Errors ParseSdfWorld(const sdf::World &_world, pxr::UsdStageRefPtr &_stage,
const std::string &_path)
{
+ sdf::Errors errors;
_stage->SetMetadata(pxr::UsdGeomTokens->upAxis, pxr::UsdGeomTokens->z);
_stage->SetEndTimeCode(100);
_stage->SetMetadata(pxr::TfToken("metersPerUnit"), 1.0);
@@ -57,6 +61,6 @@ namespace usd
<< "the moment. Models and lights that are children of the world "
<< "are currently being ignored.\n";
- return true;
+ return errors;
}
}
diff --git a/usd/src/World_Sdf2Usd_TEST.cc b/usd/src/World_Sdf2Usd_TEST.cc
index 2c52c26ad..a781d3c8c 100644
--- a/usd/src/World_Sdf2Usd_TEST.cc
+++ b/usd/src/World_Sdf2Usd_TEST.cc
@@ -18,6 +18,8 @@
#include
#include
+#pragma push_macro ("__DEPRECATED")
+#undef __DEPRECATED
#include
#include
#include
@@ -25,6 +27,7 @@
#include
#include
#include
+#pragma pop_macro ("__DEPRECATED")
#include "sdf/usd/World.hh"
#include "sdf/Root.hh"
@@ -57,7 +60,8 @@ TEST_F(UsdStageFixture, World)
auto world = root.WorldByIndex(0u);
const auto worldPath = std::string("/" + world->Name());
- EXPECT_TRUE(usd::ParseSdfWorld(*world, this->stage, worldPath));
+ auto usdErrors = usd::ParseSdfWorld(*world, stage, worldPath);
+ EXPECT_TRUE(usdErrors.empty());
// check top-level stage information
EXPECT_DOUBLE_EQ(100.0, this->stage->GetEndTimeCode());
diff --git a/usd/src/cmd/sdf2usd.cc b/usd/src/cmd/sdf2usd.cc
index ab2be27ed..b0999d44e 100644
--- a/usd/src/cmd/sdf2usd.cc
+++ b/usd/src/cmd/sdf2usd.cc
@@ -18,7 +18,10 @@
#include
#include
+#pragma push_macro ("__DEPRECATED")
+#undef __DEPRECATED
#include
+#pragma pop_macro ("__DEPRECATED")
#include "sdf/sdf.hh"
#include "sdf/usd/World.hh"
@@ -74,7 +77,8 @@ void runCommand(const Options &_opt)
auto stage = pxr::UsdStage::CreateInMemory();
const auto worldPath = std::string("/" + world->Name());
- if (!usd::ParseSdfWorld(*world, stage, worldPath))
+ auto usdErrors = usd::ParseSdfWorld(*world, stage, worldPath);
+ if (usdErrors.empty())
{
std::cerr << "Error parsing world [" << world->Name() << "]\n";
exit(-5);
@@ -112,7 +116,7 @@ int main(int argc, char** argv)
app.set_help_all_flag("--help-all", "Show all help");
app.add_flag_callback("--version", [](){
- std::cout << strdup(SDF_VERSION_FULL) << std::endl;
+ std::cout << SDF_VERSION_FULL << std::endl;
throw CLI::Success();
});
From 36d42fcfbd49350b371239f2f4a737ec262d6b6c Mon Sep 17 00:00:00 2001
From: ahcorde
Date: Mon, 17 Jan 2022 13:32:14 +0100
Subject: [PATCH 10/24] improved doc
Signed-off-by: ahcorde
---
usd/include/sdf/usd/World.hh | 8 +++++---
1 file changed, 5 insertions(+), 3 deletions(-)
diff --git a/usd/include/sdf/usd/World.hh b/usd/include/sdf/usd/World.hh
index 605831ad2..e2cc94272 100644
--- a/usd/include/sdf/usd/World.hh
+++ b/usd/include/sdf/usd/World.hh
@@ -25,6 +25,8 @@
#include
#pragma pop_macro ("__DEPRECATED")
+#include "sdf/sdf_config.h"
+#include "sdf/system_util.hh"
#include "sdf/World.hh"
namespace usd
@@ -32,11 +34,11 @@ namespace usd
/// \brief Parse an SDF world into a USD stage.
/// \param[in] _world The SDF world to parse.
/// \param[in] _stage The stage that should contain the USD representation
- /// of _world.
+ /// of _world. It must be initialized first
/// \param[in] _path The USD path of the parsed world in _stage, which must be
/// a valid USD path.
- /// \return True if _world was succesfully parsed into _stage with a path of
- /// _path. False otherwise.
+ /// \return Errors, which is a vector of Error objects. Each Error includes
+ /// an error code and message. An empty vector indicates no error.
sdf::Errors SDFORMAT_VISIBLE ParseSdfWorld(const sdf::World &_world,
pxr::UsdStageRefPtr &_stage, const std::string &_path);
}
From 45457236160a17e7f632d337ce0e9de4f91e2147 Mon Sep 17 00:00:00 2001
From: Ashton Larkin <42042756+adlarkin@users.noreply.github.com>
Date: Tue, 18 Jan 2022 12:26:29 -0700
Subject: [PATCH 11/24] update CMake code
Signed-off-by: Ashton Larkin <42042756+adlarkin@users.noreply.github.com>
---
CMakeLists.txt | 2 +-
usd/include/sdf/CMakeLists.txt | 1 -
2 files changed, 1 insertion(+), 2 deletions(-)
delete mode 100644 usd/include/sdf/CMakeLists.txt
diff --git a/CMakeLists.txt b/CMakeLists.txt
index 0f150351c..27604fe92 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -116,7 +116,7 @@ if (BUILD_SDF)
########################################
# Find PXR
- ign_find_package(pxr REQUIRED_BY usd PKGCONFIG pxr)
+ ign_find_package(pxr QUIET REQUIRED_BY usd PKGCONFIG pxr)
ign_configure_build(HIDE_SYMBOLS_BY_DEFAULT QUIT_IF_BUILD_ERRORS
COMPONENTS usd)
diff --git a/usd/include/sdf/CMakeLists.txt b/usd/include/sdf/CMakeLists.txt
deleted file mode 100644
index f2909dd9d..000000000
--- a/usd/include/sdf/CMakeLists.txt
+++ /dev/null
@@ -1 +0,0 @@
-ign_install_all_headers(COMPONENT usd)
From 91629c07da112face018cf167d567dd2f6a86020 Mon Sep 17 00:00:00 2001
From: ahcorde
Date: Wed, 19 Jan 2022 11:09:31 +0100
Subject: [PATCH 12/24] included namespaces
Signed-off-by: ahcorde
---
usd/include/sdf/usd/World.hh | 29 ++++++++++++++++++-----------
usd/src/World.cc | 7 +++++++
usd/src/World_Sdf2Usd_TEST.cc | 2 +-
usd/src/cmd/sdf2usd.cc | 2 +-
4 files changed, 27 insertions(+), 13 deletions(-)
diff --git a/usd/include/sdf/usd/World.hh b/usd/include/sdf/usd/World.hh
index e2cc94272..6ea54ab6a 100644
--- a/usd/include/sdf/usd/World.hh
+++ b/usd/include/sdf/usd/World.hh
@@ -29,18 +29,25 @@
#include "sdf/system_util.hh"
#include "sdf/World.hh"
-namespace usd
+namespace sdf
{
- /// \brief Parse an SDF world into a USD stage.
- /// \param[in] _world The SDF world to parse.
- /// \param[in] _stage The stage that should contain the USD representation
- /// of _world. It must be initialized first
- /// \param[in] _path The USD path of the parsed world in _stage, which must be
- /// a valid USD path.
- /// \return Errors, which is a vector of Error objects. Each Error includes
- /// an error code and message. An empty vector indicates no error.
- sdf::Errors SDFORMAT_VISIBLE ParseSdfWorld(const sdf::World &_world,
- pxr::UsdStageRefPtr &_stage, const std::string &_path);
+ // Inline bracke to help doxygen filtering.
+ inline namespace SDF_VERSION_NAMESPACE {
+ //
+ namespace usd
+ {
+ /// \brief Parse an SDF world into a USD stage.
+ /// \param[in] _world The SDF world to parse.
+ /// \param[in] _stage The stage that should contain the USD representation
+ /// of _world. It must be initialized first
+ /// \param[in] _path The USD path of the parsed world in _stage, which must be
+ /// a valid USD path.
+ /// \return Errors, which is a vector of Error objects. Each Error includes
+ /// an error code and message. An empty vector indicates no error.
+ sdf::Errors SDFORMAT_VISIBLE ParseSdfWorld(const sdf::World &_world,
+ pxr::UsdStageRefPtr &_stage, const std::string &_path);
+ }
+ }
}
#endif
diff --git a/usd/src/World.cc b/usd/src/World.cc
index 226fb97c9..32859f9a9 100644
--- a/usd/src/World.cc
+++ b/usd/src/World.cc
@@ -32,6 +32,11 @@
#include "sdf/World.hh"
+namespace sdf
+{
+// Inline bracke to help doxygen filtering.
+inline namespace SDF_VERSION_NAMESPACE {
+//
namespace usd
{
sdf::Errors ParseSdfWorld(const sdf::World &_world, pxr::UsdStageRefPtr &_stage,
@@ -64,3 +69,5 @@ namespace usd
return errors;
}
}
+}
+}
diff --git a/usd/src/World_Sdf2Usd_TEST.cc b/usd/src/World_Sdf2Usd_TEST.cc
index a781d3c8c..0883cd8af 100644
--- a/usd/src/World_Sdf2Usd_TEST.cc
+++ b/usd/src/World_Sdf2Usd_TEST.cc
@@ -60,7 +60,7 @@ TEST_F(UsdStageFixture, World)
auto world = root.WorldByIndex(0u);
const auto worldPath = std::string("/" + world->Name());
- auto usdErrors = usd::ParseSdfWorld(*world, stage, worldPath);
+ auto usdErrors = sdf::usd::ParseSdfWorld(*world, stage, worldPath);
EXPECT_TRUE(usdErrors.empty());
// check top-level stage information
diff --git a/usd/src/cmd/sdf2usd.cc b/usd/src/cmd/sdf2usd.cc
index b0999d44e..2411b3d8b 100644
--- a/usd/src/cmd/sdf2usd.cc
+++ b/usd/src/cmd/sdf2usd.cc
@@ -77,7 +77,7 @@ void runCommand(const Options &_opt)
auto stage = pxr::UsdStage::CreateInMemory();
const auto worldPath = std::string("/" + world->Name());
- auto usdErrors = usd::ParseSdfWorld(*world, stage, worldPath);
+ auto usdErrors = sdf::usd::ParseSdfWorld(*world, stage, worldPath);
if (usdErrors.empty())
{
std::cerr << "Error parsing world [" << world->Name() << "]\n";
From 63479536baaa2354bee69f4281795db88d2c058e Mon Sep 17 00:00:00 2001
From: ahcorde
Date: Wed, 19 Jan 2022 12:23:32 +0100
Subject: [PATCH 13/24] Added basic test to sdf2usd cmd
Signed-off-by: ahcorde
---
usd/src/CMakeLists.txt | 2 +-
usd/src/sdf2usd_TEST.cc | 86 +++++++++++++++++++++++++++++++++++++++++
2 files changed, 87 insertions(+), 1 deletion(-)
create mode 100644 usd/src/sdf2usd_TEST.cc
diff --git a/usd/src/CMakeLists.txt b/usd/src/CMakeLists.txt
index e1d24493d..554092755 100644
--- a/usd/src/CMakeLists.txt
+++ b/usd/src/CMakeLists.txt
@@ -19,7 +19,7 @@ target_link_libraries(${usd_target}
ign_build_tests(
TYPE UNIT
SOURCES ${gtest_sources}
- LIB_DEPS ${usd_target}
+ LIB_DEPS ${usd_target} ignition-cmake${IGN_CMAKE_VER}::utilities
INCLUDE_DIRS ${PROJECT_SOURCE_DIR}/test
)
diff --git a/usd/src/sdf2usd_TEST.cc b/usd/src/sdf2usd_TEST.cc
new file mode 100644
index 000000000..b5e4c79f3
--- /dev/null
+++ b/usd/src/sdf2usd_TEST.cc
@@ -0,0 +1,86 @@
+/*
+ * Copyright (C) 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
+
+#include
+
+#include
+#include
+
+#include "test_config.h"
+#include "test_utils.hh"
+
+#ifdef _WIN32
+ #define popen _popen
+ #define pclose _pclose
+#endif
+
+static std::string sdf2usdCommand()
+{
+ return std::string(IGN_PATH) + "/sdf2usd";
+}
+
+/////////////////////////////////////////////////
+std::string custom_exec_str(std::string _cmd)
+{
+ _cmd += " 2>&1";
+ FILE *pipe = popen(_cmd.c_str(), "r");
+
+ if (!pipe)
+ return "ERROR";
+
+ char buffer[128];
+ std::string result = "";
+
+ while (!feof(pipe))
+ {
+ if (fgets(buffer, 128, pipe) != NULL)
+ result += buffer;
+ }
+
+ pclose(pipe);
+ return result;
+}
+
+/////////////////////////////////////////////////
+TEST(check_cmd, IGN_UTILS_TEST_DISABLED_ON_WIN32(SDF))
+{
+ std::string pathBase = PROJECT_SOURCE_PATH;
+ pathBase = ignition::common::joinPaths(pathBase, "test", "sdf");
+
+ auto tmpDir = ignition::common::tempDirectoryPath();
+ auto tmp = ignition::common::createTempDirectory("usd", tmpDir);
+ std::cerr << "tmp " << tmp << '\n';
+ // Check a good SDF file
+ {
+ std::string path = ignition::common::joinPaths(pathBase,
+ "/shapes_world.sdf");
+
+ std::string output =
+ custom_exec_str(sdf2usdCommand() + " -i " + path + " -o " +
+ ignition::common::joinPaths(tmp, "shapes.usd"));
+ // TODO(ahcorde): Check the output when the parser is implemented
+ }
+}
+
+/////////////////////////////////////////////////
+/// Main
+int main(int argc, char **argv)
+{
+ ::testing::InitGoogleTest(&argc, argv);
+ return RUN_ALL_TESTS();
+}
From bb6ee5afa110981845b3c4839355fddd6a9cbbf5 Mon Sep 17 00:00:00 2001
From: ahcorde
Date: Wed, 19 Jan 2022 12:43:22 +0100
Subject: [PATCH 14/24] changes in sdf2usd
Signed-off-by: ahcorde
---
examples/usdConverter/README.md | 8 ++++----
usd/src/cmd/sdf2usd.cc | 6 +++---
usd/src/sdf2usd_TEST.cc | 4 +---
3 files changed, 8 insertions(+), 10 deletions(-)
diff --git a/examples/usdConverter/README.md b/examples/usdConverter/README.md
index 323fea82c..f72cb69cc 100644
--- a/examples/usdConverter/README.md
+++ b/examples/usdConverter/README.md
@@ -19,12 +19,12 @@ make
```
You should now have an executable named `sdf2usd`, which can be used to convert a SDF world file to a USD file.
-The following command converts the example `shapes.sdf` file to its USD representation, stored in a file called `shapes.usda` (run this command from the `build` directory):
+The following command converts the example `shapes.sdf` file to its USD representation, stored in a file called `shapes.usd` (run this command from the `build` directory):
```bash
-./sdf2usd ../shapes.sdf shapes.usda
+./sdf2usd ../shapes.sdf shapes.usd
```
You can now view the contents of the generated USD file with `usdview` (this should have been installed when setting up the USD dependency):
-```
-usdview shapes.usda
+```bash
+usdview shapes.usd
```
diff --git a/usd/src/cmd/sdf2usd.cc b/usd/src/cmd/sdf2usd.cc
index 2411b3d8b..9b5854298 100644
--- a/usd/src/cmd/sdf2usd.cc
+++ b/usd/src/cmd/sdf2usd.cc
@@ -44,7 +44,7 @@ struct Options
std::string inputFilename{"input.sdf"};
/// \brief output filename
- std::string outputFilename{"output.sdf"};
+ std::string outputFilename{"output.usd"};
};
void runCommand(const Options &_opt)
@@ -95,11 +95,11 @@ void addFlags(CLI::App &_app)
{
auto opt = std::make_shared();
- _app.add_option("-i,--input",
+ _app.add_option("input",
opt->inputFilename,
"Input filename");
- _app.add_option("-o,--output",
+ _app.add_option("output",
opt->outputFilename,
"Output filename");
diff --git a/usd/src/sdf2usd_TEST.cc b/usd/src/sdf2usd_TEST.cc
index b5e4c79f3..b929b1f86 100644
--- a/usd/src/sdf2usd_TEST.cc
+++ b/usd/src/sdf2usd_TEST.cc
@@ -64,14 +64,12 @@ TEST(check_cmd, IGN_UTILS_TEST_DISABLED_ON_WIN32(SDF))
auto tmpDir = ignition::common::tempDirectoryPath();
auto tmp = ignition::common::createTempDirectory("usd", tmpDir);
- std::cerr << "tmp " << tmp << '\n';
// Check a good SDF file
{
std::string path = ignition::common::joinPaths(pathBase,
"/shapes_world.sdf");
-
std::string output =
- custom_exec_str(sdf2usdCommand() + " -i " + path + " -o " +
+ custom_exec_str(sdf2usdCommand() + " " + path + " " +
ignition::common::joinPaths(tmp, "shapes.usd"));
// TODO(ahcorde): Check the output when the parser is implemented
}
From d1d7af6324dc52392cc561ef9addf8bbdb835a95 Mon Sep 17 00:00:00 2001
From: ahcorde
Date: Wed, 19 Jan 2022 12:52:47 +0100
Subject: [PATCH 15/24] Fixed usd tutorial
Signed-off-by: ahcorde
---
examples/usdConverter/README.md | 13 +++----------
1 file changed, 3 insertions(+), 10 deletions(-)
diff --git a/examples/usdConverter/README.md b/examples/usdConverter/README.md
index f72cb69cc..3690b4c5f 100644
--- a/examples/usdConverter/README.md
+++ b/examples/usdConverter/README.md
@@ -10,18 +10,11 @@ You will need all of the dependencies for sdformat, along with the following add
## Setup
-Build sdformat, and then run the following commands to build the example (run these commands from this example directory):
-```bash
-mkdir build
-cd build
-cmake ..
-make
-```
+Build sdformat, you should now have an executable named `sdf2usd`, which can be used to convert a SDF world file to a USD file.
+The following command converts the example `shapes.sdf` file to its USD representation, stored in a file called `shapes.usd`:
-You should now have an executable named `sdf2usd`, which can be used to convert a SDF world file to a USD file.
-The following command converts the example `shapes.sdf` file to its USD representation, stored in a file called `shapes.usd` (run this command from the `build` directory):
```bash
-./sdf2usd ../shapes.sdf shapes.usd
+sdf2usd ../shapes.sdf shapes.usd
```
You can now view the contents of the generated USD file with `usdview` (this should have been installed when setting up the USD dependency):
From bab9e374a703af03e6b7c726481b5f13a3ab9912 Mon Sep 17 00:00:00 2001
From: ahcorde
Date: Wed, 19 Jan 2022 14:22:07 +0100
Subject: [PATCH 16/24] Removed unneeded CMakeLists.txt
Signed-off-by: ahcorde
---
usd/include/CMakeLists.txt | 1 -
1 file changed, 1 deletion(-)
delete mode 100644 usd/include/CMakeLists.txt
diff --git a/usd/include/CMakeLists.txt b/usd/include/CMakeLists.txt
deleted file mode 100644
index 9c28e4b11..000000000
--- a/usd/include/CMakeLists.txt
+++ /dev/null
@@ -1 +0,0 @@
-add_subdirectory(sdf/usd)
From cbdfa49eb4bb0c2eb0a94c99449987febe96dd81 Mon Sep 17 00:00:00 2001
From: ahcorde
Date: Wed, 19 Jan 2022 20:41:23 +0100
Subject: [PATCH 17/24] Moved CMakeLists.txt
Signed-off-by: ahcorde
---
usd/include/sdf/{usd => }/CMakeLists.txt | 0
1 file changed, 0 insertions(+), 0 deletions(-)
rename usd/include/sdf/{usd => }/CMakeLists.txt (100%)
diff --git a/usd/include/sdf/usd/CMakeLists.txt b/usd/include/sdf/CMakeLists.txt
similarity index 100%
rename from usd/include/sdf/usd/CMakeLists.txt
rename to usd/include/sdf/CMakeLists.txt
From 99fb1702b9bf0a3ed9ecb378d7006497add40b04 Mon Sep 17 00:00:00 2001
From: Ashton Larkin <42042756+adlarkin@users.noreply.github.com>
Date: Wed, 19 Jan 2022 13:53:24 -0700
Subject: [PATCH 18/24] update example docs and other nits before merge
Signed-off-by: Ashton Larkin <42042756+adlarkin@users.noreply.github.com>
---
examples/usdConverter/README.md | 48 +++++-
examples/usdConverter/shapes.sdf | 244 -------------------------------
test/test_utils.hh | 1 +
usd/include/sdf/usd/World.hh | 2 +-
usd/src/cmd/CMakeLists.txt | 2 -
usd/src/cmd/sdf2usd.cc | 13 +-
6 files changed, 54 insertions(+), 256 deletions(-)
delete mode 100644 examples/usdConverter/shapes.sdf
diff --git a/examples/usdConverter/README.md b/examples/usdConverter/README.md
index 3690b4c5f..924944959 100644
--- a/examples/usdConverter/README.md
+++ b/examples/usdConverter/README.md
@@ -7,17 +7,57 @@ This example shows how a world in a SDF file can be converted to [USD](https://g
You will need all of the dependencies for sdformat, along with the following additional dependencies:
* USD: [installation instructions](https://github.com/PixarAnimationStudios/USD/blob/release/README.md#getting-and-building-the-code)
* [ignition-common4](https://github.com/ignitionrobotics/ign-common)
+* [ignition-utils1 (including the CLI component)](https://github.com/ignitionrobotics/ign-utils)
## Setup
-Build sdformat, you should now have an executable named `sdf2usd`, which can be used to convert a SDF world file to a USD file.
-The following command converts the example `shapes.sdf` file to its USD representation, stored in a file called `shapes.usd`:
+Build sdformat. The steps below follow a traditional cmake build, but sdformat
+can also be built with [colcon](https://colcon.readthedocs.io/en/released/index.html):
+```bash
+git clone https://github.com/ignitionrobotics/sdformat.git
+cd sdformat
+mkdir build
+cd build
+cmake ..
+make
+```
+
+You should now have an executable named `sdf2usd` in the `sdformat/build/bin` directory.
+This executable can be used to convert a SDF world file to a USD file.
+To see how the executable works, run the following command from the `sdformat/build/bin` directory:
+```bash
+./sdf2usd -h
+```
+
+To convert [shapes_world.sdf](https://github.com/ignitionrobotics/sdformat/blob/sdf12/test/sdf/shapes_world.sdf) to its USD representation as a file called `shapes.usd`, run the following commands:
```bash
-sdf2usd ../shapes.sdf shapes.usd
+wget https://raw.githubusercontent.com/ignitionrobotics/sdformat/sdf12/test/sdf/shapes_world.sdf
+./sdf2usd shapes_world.sdf shapes.usd
```
-You can now view the contents of the generated USD file with `usdview` (this should have been installed when setting up the USD dependency):
+You can now view the contents of the generated USD file with `usdcat` (this should have been installed when setting up the USD dependency):
+```bash
+usdcat shapes.usd
+```
+
+To see the visual representation of the USD world, run `usdview` (this should have also been installed when setting up the USD dependency):
```bash
usdview shapes.usd
```
+
+### Note about building with colcon
+You may need to add the USD library path to your `LD_LIBRARY_PATH` environment variable after sourcing the colcon workspace.
+If the USD library path is not a part of `LD_LIBRARY_PATH`, you will probably see the following error when running the `sdf2usd` executable:
+```bash
+sdf2usd: error while loading shared libraries: libusd_usd.so: cannot open shared object file: No such file or directory
+```
+The typical USD library path is `/lib`.
+So, if you installed USD at `/usr/local/USD`, the following command on Linux properly updates the `LD_LIBRARY_PATH` environment variable:
+```bash
+export LD_LIBRARY_PATH=$LD_LIBRARY_PATH:/usr/local/USD/lib
+```
+
+Another thing to note if building with colcon is that after sourcing the workspace with sdformat,
+the `sdf2usd` executable can be run without having to go to the `sdformat/build/bin` directory.
+So, instead of going to that directory and running `./sdf2usd ...`, you should be able to run `sdf2usd ...` from anywhere.
diff --git a/examples/usdConverter/shapes.sdf b/examples/usdConverter/shapes.sdf
deleted file mode 100644
index 6935ae5d3..000000000
--- a/examples/usdConverter/shapes.sdf
+++ /dev/null
@@ -1,244 +0,0 @@
-
-
-
-
-
- 1.0 1.0 1.0
- 0.8 0.8 0.8
-
-
-
- true
- 0 0 10 0 0 0
- 0.8 0.8 0.8 1
- 0.2 0.2 0.2 1
-
- 1000
- 0.9
- 0.01
- 0.001
-
- -0.5 0.1 -0.9
-
-
-
- true
-
-
-
-
- 0 0 1
- 100 100
-
-
-
-
-
-
- 0 0 1
- 100 100
-
-
-
- 0.8 0.8 0.8 1
- 0.8 0.8 0.8 1
- 0.8 0.8 0.8 1
-
-
-
-
-
-
- 0 0 0.5 0 0 0
-
-
-
- 0.16666
- 0
- 0
- 0.16666
- 0
- 0.16666
-
- 1.0
-
-
-
-
- 1 1 1
-
-
-
-
-
-
-
- 1 1 1
-
-
-
- 1 0 0 1
- 1 0 0 1
- 1 0 0 1
-
-
-
-
-
-
- 0 -1.5 0.5 0 0 0
-
-
-
- 0.1458
- 0
- 0
- 0.1458
- 0
- 0.125
-
- 1.0
-
-
-
-
- 0.5
- 1.0
-
-
-
-
-
-
-
- 0.5
- 1.0
-
-
-
- 0 1 0 1
- 0 1 0 1
- 0 1 0 1
-
-
-
-
-
-
- 0 1.5 0.5 0 0 0
-
-
-
- 0.1
- 0
- 0
- 0.1
- 0
- 0.1
-
- 1.0
-
-
-
-
- 0.5
-
-
-
-
-
-
-
- 0.5
-
-
-
- 0 0 1 1
- 0 0 1 1
- 0 0 1 1
-
-
-
-
-
-
- 0 -3.0 0.5 0 0 0
-
-
-
- 0.074154
- 0
- 0
- 0.074154
- 0
- 0.018769
-
- 1.0
-
-
-
-
- 0.2
- 0.6
-
-
-
-
-
-
- 0.2
- 0.6
-
-
-
- 1 1 0 1
- 1 1 0 1
- 1 1 0 1
-
-
-
-
-
-
- 0 3.0 0.5 0 0 0
-
-
-
- 0.068
- 0
- 0
- 0.058
- 0
- 0.026
-
- 1.0
-
-
-
-
- 0.2 0.3 0.5
-
-
-
-
-
-
- 0.2 0.3 0.5
-
-
-
- 1 0 1 1
- 1 0 1 1
- 1 0 1 1
-
-
-
-
-
-
diff --git a/test/test_utils.hh b/test/test_utils.hh
index e52599dad..df8e9c43f 100644
--- a/test/test_utils.hh
+++ b/test/test_utils.hh
@@ -19,6 +19,7 @@
#include
#include
+
#include "sdf/Console.hh"
#include "sdf/Root.hh"
diff --git a/usd/include/sdf/usd/World.hh b/usd/include/sdf/usd/World.hh
index 6ea54ab6a..1988af244 100644
--- a/usd/include/sdf/usd/World.hh
+++ b/usd/include/sdf/usd/World.hh
@@ -25,7 +25,7 @@
#include
#pragma pop_macro ("__DEPRECATED")
-#include "sdf/sdf_config.h"
+#include "sdf/config.hh"
#include "sdf/system_util.hh"
#include "sdf/World.hh"
diff --git a/usd/src/cmd/CMakeLists.txt b/usd/src/cmd/CMakeLists.txt
index 3fa27abc5..46b6ca8a3 100644
--- a/usd/src/cmd/CMakeLists.txt
+++ b/usd/src/cmd/CMakeLists.txt
@@ -6,8 +6,6 @@ if(TARGET ${usd_target})
target_link_libraries(sdf2usd
PUBLIC
ignition-utils${IGN_UTILS_VER}::ignition-utils${IGN_UTILS_VER}
- ignition-common${IGN_COMMON_VER}::ignition-common${IGN_COMMON_VER}
- ignition-common${IGN_COMMON_VER}::graphics
${usd_target}
)
diff --git a/usd/src/cmd/sdf2usd.cc b/usd/src/cmd/sdf2usd.cc
index 9b5854298..84248ddc6 100644
--- a/usd/src/cmd/sdf2usd.cc
+++ b/usd/src/cmd/sdf2usd.cc
@@ -78,9 +78,12 @@ void runCommand(const Options &_opt)
const auto worldPath = std::string("/" + world->Name());
auto usdErrors = sdf::usd::ParseSdfWorld(*world, stage, worldPath);
- if (usdErrors.empty())
+ if (!usdErrors.empty())
{
- std::cerr << "Error parsing world [" << world->Name() << "]\n";
+ std::cerr << "The following errors occurred when parsing world ["
+ << world->Name() << "]\n:";
+ for (const auto &e : errors)
+ std::cout << e << "\n";
exit(-5);
}
@@ -97,11 +100,11 @@ void addFlags(CLI::App &_app)
_app.add_option("input",
opt->inputFilename,
- "Input filename");
+ "Input filename. Defaults to input.sdf unless otherwise specified.");
_app.add_option("output",
opt->outputFilename,
- "Output filename");
+ "Output filename. Defaults to output.usd unless otherwise specified.");
_app.callback([&_app, opt](){
runCommand(*opt);
@@ -111,7 +114,7 @@ void addFlags(CLI::App &_app)
//////////////////////////////////////////////////
int main(int argc, char** argv)
{
- CLI::App app{"Sdf format converter"};
+ CLI::App app{"SDF to USD converter"};
app.set_help_all_flag("--help-all", "Show all help");
From 92eca6331ff67586e00e86be81e2e9d9ce125258 Mon Sep 17 00:00:00 2001
From: ahcorde
Date: Wed, 19 Jan 2022 22:32:11 +0100
Subject: [PATCH 19/24] clean CI
Signed-off-by: ahcorde
---
.github/ci/before_cmake.sh | 2 +-
.github/workflows/ci.yml | 5 -----
2 files changed, 1 insertion(+), 6 deletions(-)
diff --git a/.github/ci/before_cmake.sh b/.github/ci/before_cmake.sh
index a0e23f85c..7ad653397 100644
--- a/.github/ci/before_cmake.sh
+++ b/.github/ci/before_cmake.sh
@@ -6,7 +6,7 @@ BUILD_DIR=`pwd`
cd /tmp
-# check that we can compile USD from sources
+# check that we can compile USD from sources (only Focal)
mkdir cmake_test
cd cmake_test
diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml
index 613c0531d..277bab16a 100644
--- a/.github/workflows/ci.yml
+++ b/.github/workflows/ci.yml
@@ -7,11 +7,6 @@ jobs:
runs-on: ubuntu-latest
name: Ubuntu Bionic CI
steps:
- - name: Set env
- run: |
- export PATH=$PATH:/tmp/usd_binaries/bin
- export LD_LIBRARY_PATH=$LD_LIBRARY_PATH:/tmp/usd_binaries/lib
- export CMAKE_PREFIX_PATH=$CMAKE_PREFIX_PATH:/tmp/usd_binaries
- name: Checkout
uses: actions/checkout@v2
- name: Compile and test
From 0618353bf930778bb1e21ff34b5cf4f8babe93a2 Mon Sep 17 00:00:00 2001
From: ahcorde
Date: Wed, 19 Jan 2022 22:39:10 +0100
Subject: [PATCH 20/24] Fixed CMake warning
Signed-off-by: ahcorde
---
CMakeLists.txt | 7 +++++--
1 file changed, 5 insertions(+), 2 deletions(-)
diff --git a/CMakeLists.txt b/CMakeLists.txt
index 27604fe92..6328a7fa8 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -118,8 +118,11 @@ if (BUILD_SDF)
# Find PXR
ign_find_package(pxr QUIET REQUIRED_BY usd PKGCONFIG pxr)
- ign_configure_build(HIDE_SYMBOLS_BY_DEFAULT QUIT_IF_BUILD_ERRORS
- COMPONENTS usd)
+ if (pxr_FOUND)
+ ign_configure_build(HIDE_SYMBOLS_BY_DEFAULT QUIT_IF_BUILD_ERRORS
+ COMPONENTS usd)
+ endif()
+
ign_create_packages()
add_subdirectory(sdf)
From bcc282b9346e14f7f60138fec2b1d8caeb652999 Mon Sep 17 00:00:00 2001
From: ahcorde
Date: Wed, 19 Jan 2022 22:49:13 +0100
Subject: [PATCH 21/24] Fixed cmake
Signed-off-by: ahcorde
---
CMakeLists.txt | 6 ++++--
1 file changed, 4 insertions(+), 2 deletions(-)
diff --git a/CMakeLists.txt b/CMakeLists.txt
index 6328a7fa8..ae7a2d2bd 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -119,10 +119,12 @@ if (BUILD_SDF)
ign_find_package(pxr QUIET REQUIRED_BY usd PKGCONFIG pxr)
if (pxr_FOUND)
- ign_configure_build(HIDE_SYMBOLS_BY_DEFAULT QUIT_IF_BUILD_ERRORS
- COMPONENTS usd)
+ list(APPEND COMPONENTS_TO_BUILD usd)
endif()
+ ign_configure_build(HIDE_SYMBOLS_BY_DEFAULT QUIT_IF_BUILD_ERRORS
+ COMPONENTS ${COMPONENTS_TO_BUILD})
+
ign_create_packages()
add_subdirectory(sdf)
From 0fd25685264109aa7c05024aa5bf9b8d82ee15a8 Mon Sep 17 00:00:00 2001
From: ahcorde
Date: Wed, 19 Jan 2022 23:12:04 +0100
Subject: [PATCH 22/24] reverted changes in CMakeLists.txt
Signed-off-by: ahcorde
---
CMakeLists.txt | 6 +-----
1 file changed, 1 insertion(+), 5 deletions(-)
diff --git a/CMakeLists.txt b/CMakeLists.txt
index ae7a2d2bd..1b69c0e65 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -118,12 +118,8 @@ if (BUILD_SDF)
# Find PXR
ign_find_package(pxr QUIET REQUIRED_BY usd PKGCONFIG pxr)
- if (pxr_FOUND)
- list(APPEND COMPONENTS_TO_BUILD usd)
- endif()
-
ign_configure_build(HIDE_SYMBOLS_BY_DEFAULT QUIT_IF_BUILD_ERRORS
- COMPONENTS ${COMPONENTS_TO_BUILD})
+ COMPONENTS usd)
ign_create_packages()
From 5d2c902be843059f3beb23eab08ae14c06d5b265 Mon Sep 17 00:00:00 2001
From: Ashton Larkin <42042756+adlarkin@users.noreply.github.com>
Date: Wed, 19 Jan 2022 16:41:33 -0700
Subject: [PATCH 23/24] fix namespaces and build warnings, use sdf::Errors, set
usdLux intensity attr
Signed-off-by: Ashton Larkin <42042756+adlarkin@users.noreply.github.com>
---
usd/include/sdf/usd/Light.hh | 35 ++++++++++-----
usd/include/sdf/usd/Utils.hh | 85 ++++++++++++++++++++---------------
usd/src/Light.cc | 65 ++++++++++++++++-----------
usd/src/Light_Sdf2Usd_TEST.cc | 24 ++++++++--
usd/src/UsdTestUtils.hh | 9 ++++
usd/src/World.cc | 13 +++---
6 files changed, 148 insertions(+), 83 deletions(-)
diff --git a/usd/include/sdf/usd/Light.hh b/usd/include/sdf/usd/Light.hh
index ffaff51e1..fa9a0742d 100644
--- a/usd/include/sdf/usd/Light.hh
+++ b/usd/include/sdf/usd/Light.hh
@@ -20,23 +20,34 @@
#include
+#pragma push_macro ("__DEPRECATED")
+#undef __DEPRECATED
#include
+#pragma pop_macro ("__DEPRECATED")
+#include "sdf/config.hh"
+#include "sdf/system_util.hh"
#include "sdf/Light.hh"
-#include "sdf/sdf_config.h"
-namespace usd
+namespace sdf
{
- /// \brief Parse an SDF light into a USD stage.
- /// \param[in] _light The SDF light to parse.
- /// \param[in] _stage The stage that should contain the USD representation
- /// of _light.
- /// \param[in] _path The USD path of the parsed light in _stage, which must be
- /// a valid USD path.
- /// \return True if _light was succesfully parsed into _stage with a path of
- /// _path. False otherwise.
- bool SDFORMAT_VISIBLE ParseSdfLight(const sdf::Light &_light,
- pxr::UsdStageRefPtr &_stage, const std::string &_path);
+ // Inline bracke to help doxygen filtering.
+ inline namespace SDF_VERSION_NAMESPACE {
+ //
+ namespace usd
+ {
+ /// \brief Parse an SDF light into a USD stage.
+ /// \param[in] _light The SDF light to parse.
+ /// \param[in] _stage The stage that should contain the USD representation
+ /// of _light.
+ /// \param[in] _path The USD path of the parsed light in _stage, which must
+ /// be a valid USD path.
+ /// \return Errors, which is a vector of Error objects. Each Error includes
+ /// an error code and message. An empty vector indicates no error.
+ sdf::Errors SDFORMAT_VISIBLE ParseSdfLight(const sdf::Light &_light,
+ pxr::UsdStageRefPtr &_stage, const std::string &_path);
+ }
+ }
}
#endif
diff --git a/usd/include/sdf/usd/Utils.hh b/usd/include/sdf/usd/Utils.hh
index 4a2cf7c72..78c3a2478 100644
--- a/usd/include/sdf/usd/Utils.hh
+++ b/usd/include/sdf/usd/Utils.hh
@@ -23,55 +23,66 @@
#include
#include
#include
+#pragma push_macro ("__DEPRECATED")
+#undef __DEPRECATED
#include
+#pragma pop_macro ("__DEPRECATED")
#include
#include "sdf/SemanticPose.hh"
-#include "sdf/sdf_config.h"
+#include "sdf/config.hh"
+#include "sdf/system_util.hh"
-namespace usd
+namespace sdf
{
- /// \brief Get an object's pose w.r.t. its parent.
- /// \param[in] _obj The object whose pose should be computed/retrieved.
- /// \tparam T An object that has the following method signatures:
- /// sdf::SemanticPose SemanticPose();
- /// \return _obj's pose w.r.t. its parent. If there was an error computing
- /// this pose, the pose's position will be NaNs.
- template
- inline ignition::math::Pose3d SDFORMAT_VISIBLE PoseWrtParent(const T &_obj)
+ // Inline bracke to help doxygen filtering.
+ inline namespace SDF_VERSION_NAMESPACE {
+ //
+ namespace usd
{
- ignition::math::Pose3d pose(ignition::math::Vector3d::NaN,
- ignition::math::Quaterniond::Identity);
- auto errors = _obj.SemanticPose().Resolve(pose, "");
- if (!errors.empty())
+ /// \brief Get an object's pose w.r.t. its parent.
+ /// \param[in] _obj The object whose pose should be computed/retrieved.
+ /// \tparam T An object that has the following method signatures:
+ /// sdf::SemanticPose SemanticPose();
+ /// \return _obj's pose w.r.t. its parent. If there was an error computing
+ /// this pose, the pose's position will be NaNs.
+ template
+ inline ignition::math::Pose3d SDFORMAT_VISIBLE PoseWrtParent(const T &_obj)
{
- std::cerr << "Errors occurred when resolving the pose of ["
- << _obj.Name() << "] w.r.t its parent:\n\t" << errors;
+ ignition::math::Pose3d pose(ignition::math::Vector3d::NaN,
+ ignition::math::Quaterniond::Identity);
+ auto errors = _obj.SemanticPose().Resolve(pose, "");
+ if (!errors.empty())
+ {
+ std::cerr << "Errors occurred when resolving the pose of ["
+ << _obj.Name() << "] w.r.t its parent:\n\t" << errors;
+ }
+ return pose;
}
- return pose;
- }
- /// \brief Set the pose of a USD prim.
- /// \param[in] _pose The pose to set.
- /// \param[in] _stage The stage that contains the USD prim at path _usdPath.
- /// \param[in] _usdPath The path to the USD prim that should have its
- /// pose modified to match _pose.
- inline void SDFORMAT_VISIBLE SetPose(const ignition::math::Pose3d &_pose,
- pxr::UsdStageRefPtr &_stage, const pxr::SdfPath &_usdPath)
- {
- pxr::UsdGeomXformCommonAPI geomXformAPI(_stage->GetPrimAtPath(_usdPath));
+ /// \brief Set the pose of a USD prim.
+ /// \param[in] _pose The pose to set.
+ /// \param[in] _stage The stage that contains the USD prim at path _usdPath.
+ /// \param[in] _usdPath The path to the USD prim that should have its
+ /// pose modified to match _pose.
+ inline void SDFORMAT_VISIBLE SetPose(const ignition::math::Pose3d &_pose,
+ pxr::UsdStageRefPtr &_stage, const pxr::SdfPath &_usdPath)
+ {
+ pxr::UsdGeomXformCommonAPI geomXformAPI(_stage->GetPrimAtPath(_usdPath));
- const auto &position = _pose.Pos();
- geomXformAPI.SetTranslate(pxr::GfVec3d(
- position.X(), position.Y(), position.Z()));
+ const auto &position = _pose.Pos();
+ geomXformAPI.SetTranslate(pxr::GfVec3d(
+ position.X(), position.Y(), position.Z()));
- const auto &rotation = _pose.Rot();
- // roll/pitch/yaw from ignition::math::Pose3d are in radians, but this API
- // call expects degrees
- geomXformAPI.SetRotate(pxr::GfVec3f(
- ignition::math::Angle(rotation.Roll()).Degree(),
- ignition::math::Angle(rotation.Pitch()).Degree(),
- ignition::math::Angle(rotation.Yaw()).Degree()));
+ const auto &rotation = _pose.Rot();
+ // roll/pitch/yaw from ignition::math::Pose3d are in radians, but this API
+ // call expects degrees
+ geomXformAPI.SetRotate(pxr::GfVec3f(
+ ignition::math::Angle(rotation.Roll()).Degree(),
+ ignition::math::Angle(rotation.Pitch()).Degree(),
+ ignition::math::Angle(rotation.Yaw()).Degree()));
+ }
+ }
}
}
diff --git a/usd/src/Light.cc b/usd/src/Light.cc
index a172cb4ef..db7479d9d 100644
--- a/usd/src/Light.cc
+++ b/usd/src/Light.cc
@@ -24,20 +24,29 @@
#include
#include
#include
+#include
#include
#include
+#pragma push_macro ("__DEPRECATED")
+#undef __DEPRECATED
#include
+#pragma pop_macro ("__DEPRECATED")
#include "sdf/Light.hh"
#include "sdf/usd/Utils.hh"
+namespace sdf
+{
+// Inline bracke to help doxygen filtering.
+inline namespace SDF_VERSION_NAMESPACE {
+//
namespace usd
{
- bool ParseSdfLight(const sdf::Light &_light, pxr::UsdStageRefPtr &_stage,
- const std::string &_path)
+ sdf::Errors ParseSdfLight(const sdf::Light &_light,
+ pxr::UsdStageRefPtr &_stage, const std::string &_path)
{
const pxr::SdfPath sdfLightPath(_path);
- bool typeParsed = true;
+ sdf::Errors errors;
switch (_light.Type())
{
case sdf::LightType::POINT:
@@ -55,33 +64,37 @@ namespace usd
break;
case sdf::LightType::INVALID:
default:
- std::cerr << "Light type is either invalid or not supported\n";
- typeParsed = false;
+ errors.push_back(sdf::Error(sdf::ErrorCode::ATTRIBUTE_INCORRECT_TYPE,
+ "The light type that was given cannot be parsed to USD."));
+ return errors;
}
- if (typeParsed)
- {
- // TODO(adlarkin) incorporate sdf::Light's somehow? According
- // to the USD API, things like UsdLuxDistantLight and UsdLuxDiskLight emit
- // light along the -Z axis, so I'm not sure if this can be changed.
- usd::SetPose(usd::PoseWrtParent(_light), _stage, sdfLightPath);
+ // TODO(adlarkin) incorporate sdf::Light's somehow? According
+ // to the USD API, things like UsdLuxDistantLight and UsdLuxDiskLight emit
+ // light along the -Z axis, so I'm not sure if this can be changed.
+ sdf::usd::SetPose(sdf::usd::PoseWrtParent(_light), _stage, sdfLightPath);
- // This is a workaround to set the light's intensity attribute. Using the
- // UsdLuxLightAPI sets the light's inputs:intensity attribute, but isaac
- // sim reads the light's intensity attribute
- auto lightPrim = _stage->GetPrimAtPath(sdfLightPath);
- lightPrim.CreateAttribute(pxr::TfToken("intensity"),
- pxr::SdfValueTypeNames->Float, false).Set(
- static_cast(_light.Intensity()) * 100.0f);
+ // This is a workaround to set the light's intensity attribute. Using the
+ // UsdLuxLightAPI sets the light's "inputs:intensity" attribute, but isaac
+ // sim reads the light's "intensity" attribute. Both inputs:intensity and
+ // intensity are set to provide flexibility with other USD renderers
+ const float usdLightIntensity =
+ static_cast(_light.Intensity()) * 100.0f;
+ auto lightPrim = _stage->GetPrimAtPath(sdfLightPath);
+ lightPrim.CreateAttribute(pxr::TfToken("intensity"),
+ pxr::SdfValueTypeNames->Float, false).Set(usdLightIntensity);
+ auto lightAPI = pxr::UsdLuxLightAPI(lightPrim);
+ lightAPI.CreateIntensityAttr().Set(usdLightIntensity);
- // TODO(adlarkin) Other things to look at (there may be more):
- // * exposure - I don't think SDF has this, but USD does. See the
- // UsdLightAPI::GetExposureAttr method
- // * diffuse, specular - USD takes it as a scalar multiplier,
- // SDF takes it as a RGB color vector. Perhaps this can be handled by
- // applying a material to a light
- }
+ // TODO(adlarkin) Other things to look at (there may be more):
+ // * exposure - I don't think SDF has this, but USD does. See the
+ // UsdLightAPI::GetExposureAttr method
+ // * diffuse, specular - USD takes it as a scalar multiplier,
+ // SDF takes it as a RGB color vector. Perhaps this can be handled by
+ // applying a material to a light
- return typeParsed;
+ return errors;
}
}
+}
+}
diff --git a/usd/src/Light_Sdf2Usd_TEST.cc b/usd/src/Light_Sdf2Usd_TEST.cc
index d0ffa117a..bf5b05a6a 100644
--- a/usd/src/Light_Sdf2Usd_TEST.cc
+++ b/usd/src/Light_Sdf2Usd_TEST.cc
@@ -19,6 +19,8 @@
#include
#include
+#pragma push_macro ("__DEPRECATED")
+#undef __DEPRECATED
#include
#include
#include
@@ -27,6 +29,7 @@
#include
#include
#include
+#pragma pop_macro ("__DEPRECATED")
#include "sdf/Light.hh"
#include "sdf/Root.hh"
@@ -51,15 +54,28 @@ class UsdLightStageFixture : public ::testing::Test
public: void CheckLightIntensity(const pxr::UsdPrim &_lightPrim,
const sdf::Light &_sdfLight)
{
+ const float targetIntensity = _sdfLight.Intensity() * 100.0f;
+
bool checkedIntensity = false;
if (auto intensityAttr = _lightPrim.GetAttribute(pxr::TfToken("intensity")))
{
float intensityVal = 0.0;
intensityAttr.Get(&intensityVal);
- EXPECT_FLOAT_EQ(intensityVal, _sdfLight.Intensity() * 100.0f);
+ EXPECT_FLOAT_EQ(intensityVal, targetIntensity);
checkedIntensity = true;
}
EXPECT_TRUE(checkedIntensity);
+
+ bool checkedInputIntensity = false;
+ if (auto intensityAttr = _lightPrim.GetAttribute(
+ pxr::TfToken("inputs:intensity")))
+ {
+ float intensityVal = 0.0;
+ intensityAttr.Get(&intensityVal);
+ EXPECT_FLOAT_EQ(intensityVal, targetIntensity);
+ checkedInputIntensity = true;
+ }
+ EXPECT_TRUE(checkedInputIntensity);
}
protected: void SetUp() override
@@ -91,7 +107,8 @@ TEST_F(UsdLightStageFixture, Lights)
const auto light = *(world->LightByIndex(i));
const auto lightPath = std::string("/" + light.Name());
lightPathToSdf[lightPath] = light;
- EXPECT_TRUE(usd::ParseSdfLight(light, this->stage, lightPath));
+ const auto errors = sdf::usd::ParseSdfLight(light, this->stage, lightPath);
+ EXPECT_TRUE(errors.empty());
}
EXPECT_EQ(world->LightCount(), lightPathToSdf.size());
@@ -138,7 +155,8 @@ TEST_F(UsdLightStageFixture, Lights)
if (validLight)
{
this->CheckLightIntensity(lightUsd, lightSdf);
- usd::testing::CheckPrimPose(lightUsd, usd::PoseWrtParent(lightSdf));
+ sdf::usd::testing::CheckPrimPose(lightUsd,
+ sdf::usd::PoseWrtParent(lightSdf));
}
}
EXPECT_EQ(1, numPointLights);
diff --git a/usd/src/UsdTestUtils.hh b/usd/src/UsdTestUtils.hh
index 6670bb3ce..c265f6b30 100644
--- a/usd/src/UsdTestUtils.hh
+++ b/usd/src/UsdTestUtils.hh
@@ -25,6 +25,13 @@
#include
#include
+#include "sdf/system_util.hh"
+
+namespace sdf
+{
+// Inline bracke to help doxygen filtering.
+inline namespace SDF_VERSION_NAMESPACE {
+//
namespace usd
{
namespace testing
@@ -89,5 +96,7 @@ void CheckPrimPose(const pxr::UsdPrim &_usdPrim,
} // namespace testing
} // namespace usd
+}
+} // namespace sdf
#endif
diff --git a/usd/src/World.cc b/usd/src/World.cc
index 88f4e1e74..f95cdffd7 100644
--- a/usd/src/World.cc
+++ b/usd/src/World.cc
@@ -66,16 +66,19 @@ namespace usd
{
const auto light = *(_world.LightByIndex(i));
const auto lightPath = std::string(_path + "/" + light.Name());
- if (!ParseSdfLight(light, _stage, lightPath))
+ const auto lightErrors = ParseSdfLight(light, _stage, lightPath);
+ if (!lightErrors.empty())
{
- std::cerr << "Error parsing light [" << light.Name() << "]\n";
- return false;
+ std::cerr << "Error(s) occurred parsing light [" << light.Name() << "]\n";
+ for (const auto &e : lightErrors)
+ errors.push_back(e);
+ return errors;
}
}
// TODO(ahcorde) Add parser
- std::cerr << "Parser for a sdf world only parses physics information at "
- << "the moment. Models that are children of the world "
+ std::cerr << "Parser for a sdf world only parses physics information and "
+ << "lights at the moment. Models that are children of the world "
<< "are currently being ignored.\n";
return errors;
From d14dc37273e2a8a0a724106eadb86f66e493b66f Mon Sep 17 00:00:00 2001
From: Ashton Larkin <42042756+adlarkin@users.noreply.github.com>
Date: Mon, 24 Jan 2022 16:18:42 -0700
Subject: [PATCH 24/24] update to work with sdf12 branch
Signed-off-by: Ashton Larkin <42042756+adlarkin@users.noreply.github.com>
---
.github/ci/packages.apt | 1 -
usd/include/sdf/usd/World.hh | 53 -----------
usd/include/sdf/usd/{ => sdf_parser}/Light.hh | 8 +-
usd/include/sdf/usd/{ => sdf_parser}/Utils.hh | 13 ++-
usd/src/CMakeLists.txt | 6 +-
usd/src/World.cc | 88 ------------------
usd/src/World_Sdf2Usd_TEST.cc | 91 -------------------
usd/src/sdf2usd_TEST.cc | 84 -----------------
usd/src/{ => sdf_parser}/Light.cc | 4 +-
.../{ => sdf_parser}/Light_Sdf2Usd_TEST.cc | 4 +-
usd/src/{ => sdf_parser}/UsdTestUtils.hh | 4 +-
11 files changed, 24 insertions(+), 332 deletions(-)
delete mode 100644 usd/include/sdf/usd/World.hh
rename usd/include/sdf/usd/{ => sdf_parser}/Light.hh (83%)
rename usd/include/sdf/usd/{ => sdf_parser}/Utils.hh (90%)
delete mode 100644 usd/src/World.cc
delete mode 100644 usd/src/World_Sdf2Usd_TEST.cc
delete mode 100644 usd/src/sdf2usd_TEST.cc
rename usd/src/{ => sdf_parser}/Light.cc (97%)
rename usd/src/{ => sdf_parser}/Light_Sdf2Usd_TEST.cc (98%)
rename usd/src/{ => sdf_parser}/UsdTestUtils.hh (97%)
diff --git a/.github/ci/packages.apt b/.github/ci/packages.apt
index ff4d5307b..09308b7f2 100644
--- a/.github/ci/packages.apt
+++ b/.github/ci/packages.apt
@@ -1,4 +1,3 @@
-libignition-common4-dev
libignition-cmake2-dev
libignition-common4-dev
libignition-math6-dev
diff --git a/usd/include/sdf/usd/World.hh b/usd/include/sdf/usd/World.hh
deleted file mode 100644
index 1988af244..000000000
--- a/usd/include/sdf/usd/World.hh
+++ /dev/null
@@ -1,53 +0,0 @@
-/*
- * Copyright (C) 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.
- *
-*/
-
-#ifndef SDF_USD_WORLD_HH_
-#define SDF_USD_WORLD_HH_
-
-#include
-
-#pragma push_macro ("__DEPRECATED")
-#undef __DEPRECATED
-#include
-#pragma pop_macro ("__DEPRECATED")
-
-#include "sdf/config.hh"
-#include "sdf/system_util.hh"
-#include "sdf/World.hh"
-
-namespace sdf
-{
- // Inline bracke to help doxygen filtering.
- inline namespace SDF_VERSION_NAMESPACE {
- //
- namespace usd
- {
- /// \brief Parse an SDF world into a USD stage.
- /// \param[in] _world The SDF world to parse.
- /// \param[in] _stage The stage that should contain the USD representation
- /// of _world. It must be initialized first
- /// \param[in] _path The USD path of the parsed world in _stage, which must be
- /// a valid USD path.
- /// \return Errors, which is a vector of Error objects. Each Error includes
- /// an error code and message. An empty vector indicates no error.
- sdf::Errors SDFORMAT_VISIBLE ParseSdfWorld(const sdf::World &_world,
- pxr::UsdStageRefPtr &_stage, const std::string &_path);
- }
- }
-}
-
-#endif
diff --git a/usd/include/sdf/usd/Light.hh b/usd/include/sdf/usd/sdf_parser/Light.hh
similarity index 83%
rename from usd/include/sdf/usd/Light.hh
rename to usd/include/sdf/usd/sdf_parser/Light.hh
index fa9a0742d..fdb260238 100644
--- a/usd/include/sdf/usd/Light.hh
+++ b/usd/include/sdf/usd/sdf_parser/Light.hh
@@ -15,11 +15,15 @@
*
*/
-#ifndef SDF_USD_LIGHT_HH_
-#define SDF_USD_LIGHT_HH_
+#ifndef SDF_USD_SDF_PARSER_LIGHT_HH_
+#define SDF_USD_SDF_PARSER_LIGHT_HH_
#include
+// TODO(adlarkin):this is to remove deprecated "warnings" in usd, these warnings
+// are reported using #pragma message so normal diagnostic flags cannot remove
+// them. This workaround requires this block to be used whenever usd is
+// included.
#pragma push_macro ("__DEPRECATED")
#undef __DEPRECATED
#include
diff --git a/usd/include/sdf/usd/Utils.hh b/usd/include/sdf/usd/sdf_parser/Utils.hh
similarity index 90%
rename from usd/include/sdf/usd/Utils.hh
rename to usd/include/sdf/usd/sdf_parser/Utils.hh
index 78c3a2478..0163efd96 100644
--- a/usd/include/sdf/usd/Utils.hh
+++ b/usd/include/sdf/usd/sdf_parser/Utils.hh
@@ -15,19 +15,24 @@
*
*/
-#ifndef SDF_USD_UTILS_HH_
-#define SDF_USD_UTILS_HH_
+#ifndef SDF_USD_SDF_PARSER_UTILS_HH_
+#define SDF_USD_SDF_PARSER_UTILS_HH_
#include
#include
#include
#include
-#include
+
+// TODO(adlarkin):this is to remove deprecated "warnings" in usd, these warnings
+// are reported using #pragma message so normal diagnostic flags cannot remove
+// them. This workaround requires this block to be used whenever usd is
+// included.
#pragma push_macro ("__DEPRECATED")
#undef __DEPRECATED
+#include
#include
-#pragma pop_macro ("__DEPRECATED")
#include
+#pragma pop_macro ("__DEPRECATED")
#include "sdf/SemanticPose.hh"
#include "sdf/config.hh"
diff --git a/usd/src/CMakeLists.txt b/usd/src/CMakeLists.txt
index 14cc51239..1dc30bbab 100644
--- a/usd/src/CMakeLists.txt
+++ b/usd/src/CMakeLists.txt
@@ -1,4 +1,5 @@
set(sources
+ sdf_parser/Light.cc
sdf_parser/World.cc
)
@@ -17,6 +18,7 @@ target_link_libraries(${usd_target}
set(gtest_sources
sdf_parser/sdf2usd_TEST.cc
+ sdf_parser/Light_Sdf2Usd_TEST.cc
sdf_parser/World_Sdf2Usd_TEST.cc
)
@@ -25,9 +27,7 @@ ign_build_tests(
TYPE UNIT
SOURCES ${gtest_sources}
LIB_DEPS ${usd_target} ignition-cmake${IGN_CMAKE_VER}::utilities
- INCLUDE_DIRS
- ${CMAKE_CURRENT_SOURCE_DIR}
- ${PROJECT_SOURCE_DIR}/test
+ INCLUDE_DIRS ${PROJECT_SOURCE_DIR}/test
)
add_subdirectory(cmd)
diff --git a/usd/src/World.cc b/usd/src/World.cc
deleted file mode 100644
index f95cdffd7..000000000
--- a/usd/src/World.cc
+++ /dev/null
@@ -1,88 +0,0 @@
-/*
- * Copyright (C) 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 "sdf/usd/World.hh"
-
-#include
-#include
-
-#include
-#include
-#include
-#pragma push_macro ("__DEPRECATED")
-#undef __DEPRECATED
-#include
-#pragma pop_macro ("__DEPRECATED")
-#include
-#include
-
-#include "sdf/World.hh"
-#include "sdf/usd/Light.hh"
-
-namespace sdf
-{
-// Inline bracke to help doxygen filtering.
-inline namespace SDF_VERSION_NAMESPACE {
-//
-namespace usd
-{
- sdf::Errors ParseSdfWorld(const sdf::World &_world, pxr::UsdStageRefPtr &_stage,
- const std::string &_path)
- {
- sdf::Errors errors;
- _stage->SetMetadata(pxr::UsdGeomTokens->upAxis, pxr::UsdGeomTokens->z);
- _stage->SetEndTimeCode(100);
- _stage->SetMetadata(pxr::TfToken("metersPerUnit"), 1.0);
- _stage->SetStartTimeCode(0);
- _stage->SetTimeCodesPerSecond(24);
-
- const pxr::SdfPath worldPrimPath(_path);
- auto usdWorldPrim = _stage->DefinePrim(worldPrimPath);
-
- auto usdPhysics = pxr::UsdPhysicsScene::Define(_stage,
- pxr::SdfPath(_path + "/physics"));
- const auto &sdfWorldGravity = _world.Gravity();
- const auto normalizedGravity = sdfWorldGravity.Normalized();
- usdPhysics.CreateGravityDirectionAttr().Set(pxr::GfVec3f(
- normalizedGravity.X(), normalizedGravity.Y(), normalizedGravity.Z()));
- usdPhysics.CreateGravityMagnitudeAttr().Set(
- static_cast(sdfWorldGravity.Length()));
-
- for (uint64_t i = 0; i < _world.LightCount(); ++i)
- {
- const auto light = *(_world.LightByIndex(i));
- const auto lightPath = std::string(_path + "/" + light.Name());
- const auto lightErrors = ParseSdfLight(light, _stage, lightPath);
- if (!lightErrors.empty())
- {
- std::cerr << "Error(s) occurred parsing light [" << light.Name() << "]\n";
- for (const auto &e : lightErrors)
- errors.push_back(e);
- return errors;
- }
- }
-
- // TODO(ahcorde) Add parser
- std::cerr << "Parser for a sdf world only parses physics information and "
- << "lights at the moment. Models that are children of the world "
- << "are currently being ignored.\n";
-
- return errors;
- }
-}
-}
-}
diff --git a/usd/src/World_Sdf2Usd_TEST.cc b/usd/src/World_Sdf2Usd_TEST.cc
deleted file mode 100644
index 0883cd8af..000000000
--- a/usd/src/World_Sdf2Usd_TEST.cc
+++ /dev/null
@@ -1,91 +0,0 @@
-/*
- * 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
-
-#include
-#pragma push_macro ("__DEPRECATED")
-#undef __DEPRECATED
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-#pragma pop_macro ("__DEPRECATED")
-
-#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());
- auto usdErrors = sdf::usd::ParseSdfWorld(*world, stage, worldPath);
- EXPECT_TRUE(usdErrors.empty());
-
- // 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);
-}
diff --git a/usd/src/sdf2usd_TEST.cc b/usd/src/sdf2usd_TEST.cc
deleted file mode 100644
index b929b1f86..000000000
--- a/usd/src/sdf2usd_TEST.cc
+++ /dev/null
@@ -1,84 +0,0 @@
-/*
- * Copyright (C) 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
-
-#include
-
-#include
-#include
-
-#include "test_config.h"
-#include "test_utils.hh"
-
-#ifdef _WIN32
- #define popen _popen
- #define pclose _pclose
-#endif
-
-static std::string sdf2usdCommand()
-{
- return std::string(IGN_PATH) + "/sdf2usd";
-}
-
-/////////////////////////////////////////////////
-std::string custom_exec_str(std::string _cmd)
-{
- _cmd += " 2>&1";
- FILE *pipe = popen(_cmd.c_str(), "r");
-
- if (!pipe)
- return "ERROR";
-
- char buffer[128];
- std::string result = "";
-
- while (!feof(pipe))
- {
- if (fgets(buffer, 128, pipe) != NULL)
- result += buffer;
- }
-
- pclose(pipe);
- return result;
-}
-
-/////////////////////////////////////////////////
-TEST(check_cmd, IGN_UTILS_TEST_DISABLED_ON_WIN32(SDF))
-{
- std::string pathBase = PROJECT_SOURCE_PATH;
- pathBase = ignition::common::joinPaths(pathBase, "test", "sdf");
-
- auto tmpDir = ignition::common::tempDirectoryPath();
- auto tmp = ignition::common::createTempDirectory("usd", tmpDir);
- // Check a good SDF file
- {
- std::string path = ignition::common::joinPaths(pathBase,
- "/shapes_world.sdf");
- std::string output =
- custom_exec_str(sdf2usdCommand() + " " + path + " " +
- ignition::common::joinPaths(tmp, "shapes.usd"));
- // TODO(ahcorde): Check the output when the parser is implemented
- }
-}
-
-/////////////////////////////////////////////////
-/// Main
-int main(int argc, char **argv)
-{
- ::testing::InitGoogleTest(&argc, argv);
- return RUN_ALL_TESTS();
-}
diff --git a/usd/src/Light.cc b/usd/src/sdf_parser/Light.cc
similarity index 97%
rename from usd/src/Light.cc
rename to usd/src/sdf_parser/Light.cc
index db7479d9d..b3a068cb6 100644
--- a/usd/src/Light.cc
+++ b/usd/src/sdf_parser/Light.cc
@@ -15,7 +15,7 @@
*
*/
-#include "sdf/usd/Light.hh"
+#include "sdf/usd/sdf_parser/Light.hh"
#include
@@ -33,7 +33,7 @@
#pragma pop_macro ("__DEPRECATED")
#include "sdf/Light.hh"
-#include "sdf/usd/Utils.hh"
+#include "sdf/usd/sdf_parser/Utils.hh"
namespace sdf
{
diff --git a/usd/src/Light_Sdf2Usd_TEST.cc b/usd/src/sdf_parser/Light_Sdf2Usd_TEST.cc
similarity index 98%
rename from usd/src/Light_Sdf2Usd_TEST.cc
rename to usd/src/sdf_parser/Light_Sdf2Usd_TEST.cc
index bf5b05a6a..7c849d1a9 100644
--- a/usd/src/Light_Sdf2Usd_TEST.cc
+++ b/usd/src/sdf_parser/Light_Sdf2Usd_TEST.cc
@@ -34,8 +34,8 @@
#include "sdf/Light.hh"
#include "sdf/Root.hh"
#include "sdf/World.hh"
-#include "sdf/usd/Light.hh"
-#include "sdf/usd/Utils.hh"
+#include "sdf/usd/sdf_parser/Light.hh"
+#include "sdf/usd/sdf_parser/Utils.hh"
#include "test_config.h"
#include "test_utils.hh"
#include "UsdTestUtils.hh"
diff --git a/usd/src/UsdTestUtils.hh b/usd/src/sdf_parser/UsdTestUtils.hh
similarity index 97%
rename from usd/src/UsdTestUtils.hh
rename to usd/src/sdf_parser/UsdTestUtils.hh
index c265f6b30..5a8812002 100644
--- a/usd/src/UsdTestUtils.hh
+++ b/usd/src/sdf_parser/UsdTestUtils.hh
@@ -14,8 +14,8 @@
* limitations under the License.
*
*/
-#ifndef SDF_USD_TEST_UTILS_HH_
-#define SDF_USD_TEST_UTILS_HH_
+#ifndef SDF_PARSER_USDTESTUTILS_HH_
+#define SDF_PARSER_USDTESTUTILS_HH_
#include
#include