Skip to content

Commit

Permalink
[parsing] Add UsdParser smoke test stub
Browse files Browse the repository at this point in the history
This turns up a slew of previously-unseen errors in our OpenUSD build
system, which we also fix here.
  • Loading branch information
jwnimmer-tri committed Feb 23, 2024
1 parent 0bde095 commit a6e9a62
Show file tree
Hide file tree
Showing 10 changed files with 300 additions and 46 deletions.
61 changes: 60 additions & 1 deletion multibody/parsing/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -224,6 +224,40 @@ drake_cc_library(
],
)

drake_cc_library(
name = "detail_usd_parser",
srcs = select({
"//tools:with_usd": [
"detail_usd_parser.cc",
],
"//conditions:default": [
"detail_usd_parser_off.cc",
],
}),
hdrs = ["detail_usd_parser.h"],
copts = [
# TODO(jwnimmer-tri) OpenUSD has a gargantuan number of warnings.
# We should really try to patch it to fix most/all of them.
"-w",
],
internal = True,
visibility = ["//visibility:private"],
interface_deps = [
":detail_misc",
":detail_parsing_workspace",
"//multibody/plant",
],
deps = [
"//common:find_runfiles",
"//common:unused",
] + select({
"//tools:with_usd": [
"@openusd_internal//:openusd",
],
"//conditions:default": [],
}),
)

drake_cc_library(
name = "detail_mujoco_parser",
srcs = ["detail_mujoco_parser.cc"],
Expand Down Expand Up @@ -703,6 +737,25 @@ drake_cc_googletest(
],
)

drake_cc_googletest(
name = "detail_usd_parser_test",
args = select({
"//tools:with_usd": [],
"//conditions:default": [
"--gtest_filter=-*",
],
}),
tags = [
# TODO(jwnimmer-tri) Re-enable this once we fix Boost problems.
"manual",
],
deps = [
":detail_usd_parser",
"//common/test_utilities:diagnostic_policy_test_base",
"//common/test_utilities:expect_throws_message",
],
)

install_files(
name = "install",
dest = "share/drake/multibody/parsing",
Expand All @@ -713,4 +766,10 @@ install_files(
visibility = ["//visibility:public"],
)

add_lint_tests(enable_clang_format_lint = False)
add_lint_tests(
cpplint_extra_srcs = [
"detail_usd_parser.cc",
"detail_usd_parser_off.cc",
],
enable_clang_format_lint = False,
)
75 changes: 75 additions & 0 deletions multibody/parsing/detail_usd_parser.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1,75 @@
#include "drake/multibody/parsing/detail_usd_parser.h"

#include <filesystem>
#include <stdexcept>
#include <string>
#include <vector>

#include "pxr/base/plug/registry.h"
#include "pxr/usd/usd/stage.h"

#include "drake/common/find_runfiles.h"
#include "drake/common/unused.h"

namespace drake {
namespace multibody {
namespace internal {

namespace fs = std::filesystem;
namespace pxr = drake_vendor_pxr;

namespace {
void InitializeOpenUsdLibrary() {
// Register all relevant plugins.
auto& registry = pxr::PlugRegistry::PlugRegistry::GetInstance();
std::vector<std::string> json_paths{{
"openusd_internal/pxr/usd/ar/plugInfo.json",
"openusd_internal/pxr/usd/ndr/plugInfo.json",
"openusd_internal/pxr/usd/sdf/plugInfo.json",
"openusd_internal/pxr/usd/usdGeom/plugInfo.json",
"openusd_internal/pxr/usd/usd/plugInfo.json",
"openusd_internal/pxr/usd/usdShade/plugInfo.json",
}};
for (const auto& json_path : json_paths) {
const RlocationOrError location = FindRunfile(json_path);
if (!location.error.empty()) {
throw std::runtime_error(location.error);
}
const fs::path info_dir = fs::path(location.abspath).parent_path();
registry.RegisterPlugins(info_dir.string());
}
}
} // namespace

UsdParser::UsdParser() {
static const int ignored = []() {
InitializeOpenUsdLibrary();
return 0;
}();
unused(ignored);
}

UsdParser::~UsdParser() = default;

std::optional<ModelInstanceIndex> UsdParser::AddModel(
const DataSource& data_source, const std::string& model_name,
const std::optional<std::string>& parent_model_name,
const ParsingWorkspace& workspace) {
unused(data_source, model_name, parent_model_name, workspace);
throw std::runtime_error("UsdParser::AddModel is not implemented");
}

std::vector<ModelInstanceIndex> UsdParser::AddAllModels(
const DataSource& data_source,
const std::optional<std::string>& parent_model_name,
const ParsingWorkspace& workspace) {
// Create a stage. This is just a simple placeholder at the moment.
pxr::UsdStageRefPtr stage = pxr::UsdStage::CreateInMemory();

unused(data_source, parent_model_name, workspace);
throw std::runtime_error("UsdParser::AddAllModels is not implemented");
}

} // namespace internal
} // namespace multibody
} // namespace drake
36 changes: 36 additions & 0 deletions multibody/parsing/detail_usd_parser.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,36 @@
#pragma once

#include <optional>
#include <string>
#include <vector>

#include "drake/multibody/parsing/detail_common.h"
#include "drake/multibody/parsing/detail_parsing_workspace.h"
#include "drake/multibody/tree/multibody_tree_indexes.h"

namespace drake {
namespace multibody {
namespace internal {

class UsdParser final : public ParserInterface {
public:
DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN(UsdParser)

UsdParser();

~UsdParser() final;

std::optional<ModelInstanceIndex> AddModel(
const DataSource& data_source, const std::string& model_name,
const std::optional<std::string>& parent_model_name,
const ParsingWorkspace& workspace) final;

std::vector<ModelInstanceIndex> AddAllModels(
const DataSource& data_source,
const std::optional<std::string>& parent_model_name,
const ParsingWorkspace& workspace) final;
};

} // namespace internal
} // namespace multibody
} // namespace drake
37 changes: 37 additions & 0 deletions multibody/parsing/detail_usd_parser_off.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1,37 @@
/* clang-format off to disable clang-format-includes */
#include "drake/multibody/parsing/detail_usd_parser.h"
/* clang-format on */

#include <stdexcept>

#include "drake/common/unused.h"

namespace drake {
namespace multibody {
namespace internal {

UsdParser::UsdParser() = default;

UsdParser::~UsdParser() = default;

std::optional<ModelInstanceIndex> UsdParser::AddModel(
const DataSource& data_source, const std::string& model_name,
const std::optional<std::string>& parent_model_name,
const ParsingWorkspace& workspace) {
unused(data_source, model_name, parent_model_name, workspace);
throw std::runtime_error(
"UsdParser is not available because WITH_USD is not ON");
}

std::vector<ModelInstanceIndex> UsdParser::AddAllModels(
const DataSource& data_source,
const std::optional<std::string>& parent_model_name,
const ParsingWorkspace& workspace) {
unused(data_source, parent_model_name, workspace);
throw std::runtime_error(
"UsdParser is not available because WITH_USD is not ON");
}

} // namespace internal
} // namespace multibody
} // namespace drake
57 changes: 57 additions & 0 deletions multibody/parsing/test/detail_usd_parser_test.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1,57 @@
#include "drake/multibody/parsing/detail_usd_parser.h"

#include <gtest/gtest.h>

#include "drake/common/test_utilities/diagnostic_policy_test_base.h"
#include "drake/common/test_utilities/expect_throws_message.h"

namespace drake {
namespace multibody {
namespace internal {
namespace {

namespace fs = std::filesystem;

using drake::internal::DiagnosticPolicy;
using geometry::SceneGraph;

class UsdParserTest : public test::DiagnosticPolicyTestBase {
public:
UsdParserTest() { plant_.RegisterAsSourceForSceneGraph(&scene_graph_); }

std::vector<ModelInstanceIndex> ParseFile(const fs::path& filename) {
const std::string source_filename = filename.string();
const DataSource source{DataSource::kFilename, &source_filename};
const std::optional<std::string> parent_model_name;
internal::CollisionFilterGroupResolver resolver{&plant_};
ParsingWorkspace w{options_, package_map_, diagnostic_policy_,
&plant_, &resolver, NoSelect};
UsdParser dut;
auto result = dut.AddAllModels(source, parent_model_name, w);
resolver.Resolve(diagnostic_policy_);
return result;
}

// USD cannot delegate to any other parsers.
static ParserInterface& NoSelect(const drake::internal::DiagnosticPolicy&,
const std::string&) {
DRAKE_UNREACHABLE();
}

protected:
ParsingOptions options_;
PackageMap package_map_;
MultibodyPlant<double> plant_{0.01};
SceneGraph<double> scene_graph_;
};

TEST_F(UsdParserTest, Stub) {
const fs::path filename{"no_such_file.usda"};
DRAKE_EXPECT_THROWS_MESSAGE(ParseFile(filename),
".*UsdParser.*AddAllModels.*not implemented.*");
}

} // namespace
} // namespace internal
} // namespace multibody
} // namespace drake
34 changes: 0 additions & 34 deletions tools/workspace/openusd_internal/BUILD.bazel
Original file line number Diff line number Diff line change
@@ -1,37 +1,3 @@
load("//tools/workspace:generate_file.bzl", "generate_file")
load("//tools/lint:lint.bzl", "add_lint_tests")

# TODO(jwnimmer-tri) To prove that the @openusd_internal build system is
# working properly, here we perform a smoke test of `usdcat --help`. Once
# we have enough real unit tests in Drake that call into USD and prove out
# the build, we should remove this simple smoke test.

alias(
name = "usdcat",
actual = "@openusd_internal//:usdcat",
tags = [
# Only compile this binary when the usdcat_help test needs it.
"manual",
],
)

generate_file(
name = "empty.sh",
# When WITH_USD is off, this serves as a test stub dummy.
content = "echo 'WITH_USD is not ON'",
)

sh_test(
name = "usdcat_help",
srcs = select({
"//tools:with_usd": [":usdcat"],
"//conditions:default": ["empty.sh"],
}),
args = ["--help"],
tags = [
# TODO(jwnimmer-tri) Re-enable this once we fix Boost problems.
"manual",
],
)

add_lint_tests()
13 changes: 12 additions & 1 deletion tools/workspace/openusd_internal/defs.bzl
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@ def pxr_library(
Args:
name: Matches the upstream name (the first argument in CMake).
subdir: The subdirectory under `OpenUSD/pxr` (e.g. "base/arch").
subdir: The subdirectory under `OpenUSD` (e.g. "pxr/base/arch").
"""
attrs = FILES[subdir]
srcs = [
Expand Down Expand Up @@ -42,11 +42,22 @@ def pxr_library(
"@onetbb_internal//:tbb",
# TODO(jwnimmer-tri) We also need to list some @boost here.
]

# TODO(jwnimmer-tri) The plugInfo files will need to be pseudo-installed.
data = native.glob([subdir + "/plugInfo.json"], allow_empty = True)

# OpenUSD uses `__attribute__((constructor))` in anger, so we must mark
# all of its code as "alwayslink" (aka "whole archive").
alwayslink = True

cc_library(
name = name,
srcs = srcs,
hdrs = hdrs,
defines = defines,
copts = ["-w"],
alwayslink = alwayslink,
linkstatic = True,
data = data,
deps = deps,
)
12 changes: 2 additions & 10 deletions tools/workspace/openusd_internal/package.BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -73,15 +73,7 @@ cc_library(
":vt",
":work",
],
alwayslink = True,
linkstatic = True,
visibility = ["//visibility:public"],
)

cc_binary(
name = "usdcat",
srcs = ["pxr/usd/bin/usdcat/usdcat.cpp"],
copts = ["-w"],
deps = [":openusd"],
visibility = [
"@drake//tools/workspace/openusd_internal:__pkg__",
],
)
20 changes: 20 additions & 0 deletions tools/workspace/openusd_internal/patches/no_gnu_ext.patch
Original file line number Diff line number Diff line change
@@ -0,0 +1,20 @@
[openusd_internal] Opt-out of GNU libstdc++ extensions

They are deprecated old smelly stuff that spews compiler warnings.
This opt-out is a Drake choice, do we don't plan to upstream this patch.

--- pxr/base/arch/defines.h
+++ pxr/base/arch/defines.h
@@ -88,10 +88,8 @@
// Features
//

-// Only use the GNU STL extensions on Linux when using gcc.
-#if defined(ARCH_OS_LINUX) && defined(ARCH_COMPILER_GCC)
-#define ARCH_HAS_GNU_STL_EXTENSIONS
-#endif
+// N.B. Drake never uses the GNU STL extensions.
+// #define ARCH_HAS_GNU_STL_EXTENSIONS

// The current version of Apple clang does not support the thread_local
// keyword.
Loading

0 comments on commit a6e9a62

Please sign in to comment.