Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

USD Parsing for RigidBody Colliders #21405

Open
wants to merge 57 commits into
base: master
Choose a base branch
from

Conversation

hong-nvidia
Copy link

@hong-nvidia hong-nvidia commented May 7, 2024

The example that I used to test the parser, which serves as a visual sanity check, is shown below:

drake_cc_binary(
    name = "usd_parser_manual_test",
    testonly = 1,
    srcs = ["test/usd_parser_manual_test.cc"],
    data = [":test_models"],
    deps = [
        ":detail_misc",
        ":detail_usd_parser",
        "//common:add_text_logging_gflags",
        "//systems/analysis:simulator",
        "//visualization",
        "@gflags",
    ],
)
#include <gflags/gflags.h>

#include "drake/multibody/parsing/detail_common.h"
#include "drake/multibody/parsing/detail_usd_parser.h"
#include "drake/multibody/plant/multibody_plant_config_functions.h"
#include "drake/systems/analysis/simulator.h"
#include "drake/visualization/visualization_config_functions.h"

namespace drake {
namespace multibody {
namespace internal {

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

int do_main(int argc, char* argv[]) {
  gflags::SetUsageMessage("[INPUT-FILE-OR-URL]\n"
                          "Run multibody parser; print errors if any");
  gflags::ParseCommandLineFlags(&argc, &argv, true);
  if (argc < 2) {
    drake::log()->error("missing input filename");
    return 1;
  }

  drake::log()->info("parsing {}", argv[1]);

  std::string filename(argv[1]);
  const DataSource source{DataSource::kFilename, &filename};

  systems::DiagramBuilder<double> builder;
  MultibodyPlantConfig plant_config;

  auto [plant, scene_graph] =
    drake::multibody::AddMultibodyPlant(plant_config, &builder);

  internal::CollisionFilterGroupResolver resolver{&plant};
  PackageMap package_map;
  ParsingOptions options;
  drake::internal::DiagnosticPolicy diagnostic_policy;
  const std::optional<std::string> parent_model_name;

  ParsingWorkspace w{options, package_map, diagnostic_policy,
                     &plant,  &resolver,   NoSelect};

  UsdParserWrapper parser;
  std::vector<ModelInstanceIndex> models;
  try {
    models = parser.AddAllModels(source, parent_model_name, w);
  } catch (const std::exception& e) {
    drake::log()->error(e.what());
    ::exit(EXIT_FAILURE);
  }
  resolver.Resolve(diagnostic_policy);

  plant.Finalize();

  visualization::AddDefaultVisualization(&builder);

  auto diagram = builder.Build();

  std::unique_ptr<systems::Context<double>> diagram_context =
      diagram->CreateDefaultContext();
  diagram->SetDefaultContext(diagram_context.get());
  systems::Context<double>& plant_context =
      diagram->GetMutableSubsystemContext(plant, diagram_context.get());

  plant.SetDefaultContext(&plant_context);

  systems::Simulator<double> simulator(*diagram, std::move(diagram_context));
  simulator.set_publish_every_time_step(false);
  simulator.set_target_realtime_rate(1.0);
  simulator.Initialize();
  simulator.AdvanceTo(5.0);
  return 0;
}

}  // namespace internal
}  // namespace multibody
}  // namespace drake

int main(int argc, char* argv[]) {
  return drake::multibody::internal::do_main(argc, argv);
}


This change is Reviewable

Copy link
Contributor

@rpoyner-tri rpoyner-tri left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

+@rpoyner-tri for feature review. I'll get to this today or tomorrow; today is my assigned platform-reviewer day.

Reviewable status: LGTM missing from assignee rpoyner-tri(platform), needs at least two assigned reviewers, commits need curation (https://drake.mit.edu/reviewable.html#curated-commits), missing label for release notes (waiting on @hong-nvidia)

Copy link
Contributor

@rpoyner-tri rpoyner-tri left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I got hung up in the TBB deprecation weeds trying to build this against local-built USD; I'll see how far I can get with desk-checking the logic and tests. Also, maybe a viable build system is near; see #21408 .

Reviewed 1 of 9 files at r1.
Reviewable status: LGTM missing from assignee rpoyner-tri(platform), needs at least two assigned reviewers, commits need curation (https://drake.mit.edu/reviewable.html#curated-commits), missing label for release notes (waiting on @hong-nvidia)

Copy link
Contributor

@rpoyner-tri rpoyner-tri left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Made some progress; more to come. If you can, try rebasing on newer master. With the merge of #21408, we can all use the bazel integrated usd to build.

Reviewed 1 of 9 files at r1.
Reviewable status: 8 unresolved discussions, LGTM missing from assignee rpoyner-tri(platform), needs at least two assigned reviewers, commits need curation (https://drake.mit.edu/reviewable.html#curated-commits), missing label for release notes (waiting on @hong-nvidia)


multibody/parsing/detail_usd_geometry.h line 10 at r1 (raw file):

namespace internal {

struct ParsingWorkspace;

Drake style does not generally approve of forward declarations. Please include the header instead.


multibody/parsing/detail_usd_geometry.h line 12 at r1 (raw file):

struct ParsingWorkspace;

Eigen::Vector3d GetBoxDimension(

All of these function declarations should have some doc; it won't be parsed by doxygen, but it should give parser developers the information they need.


multibody/parsing/detail_usd_geometry.h line 104 at r1 (raw file):

}  // namespace internal
}  // namespace multibody
}  // namespace drake

nit please keep a final newline at end of file.


multibody/parsing/detail_usd_geometry.cc line 16 at r1 (raw file):

#include "pxr/usd/usdPhysics/massAPI.h"

#include "drake/multibody/parsing/detail_parsing_workspace.h"

nit in keeping with comments above, this include can just migrate to the header file.


multibody/parsing/detail_usd_geometry.cc line 61 at r1 (raw file):

double GetPrimMass(const pxr::UsdPrim& prim, const ParsingWorkspace& w) {
  if (prim.HasAPI(pxr::TfToken("PhysicsMassAPI"))) {
    float mass = 0.f;

minor any reason not to just use a double here? Looks to me like Get() will work correctly with double.


multibody/parsing/detail_usd_geometry.cc line 64 at r1 (raw file):

    auto mass_api = pxr::UsdPhysicsMassAPI(prim);
    if (mass_api.GetMassAttr().Get(&mass)) {
      return static_cast<double>(mass);

minor assuming double works, then the cast can go away as well.


multibody/parsing/detail_usd_geometry.cc line 67 at r1 (raw file):

    }
  }
  const double default_mass = 1.0;

domain expert question: does USD generally have a specified strategy for providing default values? If so, we should probably follow what it says.

In any case, I like that this code path issues a warning.


multibody/parsing/detail_usd_geometry.cc line 434 at r1 (raw file):

}  // namespace internal
}  // namespace multibody
}  // namespace drake

nit please keep a final newline at end of file.

@hong-nvidia hong-nvidia force-pushed the simple-usd-parsing branch 3 times, most recently from 4ef6f6d to ab7dbb6 Compare May 10, 2024 21:42
@jwnimmer-tri jwnimmer-tri added the release notes: feature This pull request contains a new feature label May 10, 2024
Copy link
Author

@hong-nvidia hong-nvidia left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Reviewable status: 5 unresolved discussions, LGTM missing from assignee rpoyner-tri(platform), needs at least two assigned reviewers, commits need curation (https://drake.mit.edu/reviewable.html#curated-commits)


multibody/parsing/detail_usd_geometry.cc line 61 at r1 (raw file):

Previously, rpoyner-tri (Rick Poyner (rico)) wrote…

minor any reason not to just use a double here? Looks to me like Get() will work correctly with double.

The physics:mass attribute is, unfortunately, a single-precision type (see the function GetMassAttr() on this page). In the future, we can petition to make those physics-related attributes double precision.


multibody/parsing/detail_usd_geometry.cc line 64 at r1 (raw file):

Previously, rpoyner-tri (Rick Poyner (rico)) wrote…

minor assuming double works, then the cast can go away as well.

please see comment above


multibody/parsing/detail_usd_geometry.cc line 67 at r1 (raw file):

Previously, rpoyner-tri (Rick Poyner (rico)) wrote…

domain expert question: does USD generally have a specified strategy for providing default values? If so, we should probably follow what it says.

In any case, I like that this code path issues a warning.

I don't think USD has a mechanism to set a default value for a certain type of attribute globally. (It's able to specify the default value for some types of attributes on a per-prim basis, but that's not applicable here)

Copy link
Author

@hong-nvidia hong-nvidia left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I've rebased the branch to latest master

Reviewable status: 5 unresolved discussions, LGTM missing from assignee rpoyner-tri(platform), needs at least two assigned reviewers, commits need curation (https://drake.mit.edu/reviewable.html#curated-commits)

Copy link
Contributor

@rpoyner-tri rpoyner-tri left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Still looking, but replied to some of the discussions.

Reviewed 5 of 10 files at r2, all commit messages.
Reviewable status: 3 unresolved discussions, LGTM missing from assignee rpoyner-tri(platform), needs at least two assigned reviewers, commits need curation (https://drake.mit.edu/reviewable.html#curated-commits) (waiting on @hong-nvidia)


multibody/parsing/detail_usd_geometry.h line 37 at r3 (raw file):

  const ParsingWorkspace& w);

// Creates a geometry::Box with a dimension specified by the UsdGeomCube prim

Drake style is more picky than most about grammar and punctuation, but perhaps more generous in deciding what is a complete sentence. This comment (and most below) should end with a period (.) .


multibody/parsing/detail_usd_geometry.cc line 61 at r1 (raw file):

Previously, hong-nvidia wrote…

The physics:mass attribute is, unfortunately, a single-precision type (see the function GetMassAttr() on this page). In the future, we can petition to make those physics-related attributes double precision.

followup question (feel free to dismiss without code change): is there any harm in having the Get() API read into a double, regardless of underlying limitations?


multibody/parsing/detail_usd_geometry.cc line 67 at r1 (raw file):

Previously, hong-nvidia wrote…

I don't think USD has a mechanism to set a default value for a certain type of attribute globally. (It's able to specify the default value for some types of attributes on a per-prim basis, but that's not applicable here)

I was asking more if there are conventions or standards, aside from any implementation. For example URDF (in many places, not everywhere) specifies that default values are 0 if nothing is supplied from model file input. SDFormat tends to go the other way, inserting "reasonable" defaults if the input is silent, and (possibly worse) the sdformatlib implementation doesn't really forward the information that the input didn't supply a value. So, I'm glad that OpenUSD isn't forcing our hand; it may take a little while to decide what policy we want to implement.

Copy link
Author

@hong-nvidia hong-nvidia left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Reviewable status: 2 unresolved discussions, LGTM missing from assignee rpoyner-tri(platform), needs at least two assigned reviewers, commits need curation (https://drake.mit.edu/reviewable.html#curated-commits)


multibody/parsing/detail_usd_geometry.h line 37 at r3 (raw file):

Previously, rpoyner-tri (Rick Poyner (rico)) wrote…

Drake style is more picky than most about grammar and punctuation, but perhaps more generous in deciding what is a complete sentence. This comment (and most below) should end with a period (.) .

Fixed. Thanks Rick for pointing those out.


multibody/parsing/detail_usd_geometry.cc line 61 at r1 (raw file):

Previously, rpoyner-tri (Rick Poyner (rico)) wrote…

followup question (feel free to dismiss without code change): is there any harm in having the Get() API read into a double, regardless of underlying limitations?

If the type of the variable we pass in differs from the underlying type of the attribute, Get() will return false, indicating failure to read the value. I was hoping that USD would do an implicit cast but that's not the case here (confirmed it myself), for better or worse.


multibody/parsing/detail_usd_geometry.cc line 67 at r1 (raw file):

Previously, rpoyner-tri (Rick Poyner (rico)) wrote…

I was asking more if there are conventions or standards, aside from any implementation. For example URDF (in many places, not everywhere) specifies that default values are 0 if nothing is supplied from model file input. SDFormat tends to go the other way, inserting "reasonable" defaults if the input is silent, and (possibly worse) the sdformatlib implementation doesn't really forward the information that the input didn't supply a value. So, I'm glad that OpenUSD isn't forcing our hand; it may take a little while to decide what policy we want to implement.

I see. In the case of USD, if an attribute doesn't exist or it doesn't contain a value, the read operation would just fail.

Copy link
Contributor

@rpoyner-tri rpoyner-tri left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

More progress. Still reading, but wanted to get some of this discussion into your hands.

Reviewed 1 of 9 files at r1.
Reviewable status: 5 unresolved discussions, LGTM missing from assignee rpoyner-tri(platform), needs at least two assigned reviewers, commits need curation (https://drake.mit.edu/reviewable.html#curated-commits) (waiting on @hong-nvidia)


multibody/parsing/detail_usd_geometry.cc line 61 at r1 (raw file):

Previously, hong-nvidia wrote…

If the type of the variable we pass in differs from the underlying type of the attribute, Get() will return false, indicating failure to read the value. I was hoping that USD would do an implicit cast but that's not the case here (confirmed it myself), for better or worse.

Hm. If I understand the interface, we have no way of distinguishing "the input didn't have a value" from "the programmer chose the wrong data type". In that case, we (at least) need a unit test case to demonstrate parsing of a mass value other than the default.

Looking deeper into OpenUSD, there is a whole run-time type system (attribute->GetType(), etc.) we could interrogate. One could imagine writing a DRAKE_ASSERT to verify we picked the right type. Failure of the assert would be more precise, but would not remove the need for the end-to-end non-default value reading test. Depending on how awkward it is to write, it may not be worth it.


multibody/parsing/detail_usd_parser.cc line 161 at r4 (raw file):

    w_.diagnostic.Error(fmt::format("Unsupported Prim type: {}", prim_type));
  }
  return w_.plant->AddRigidBody(

Using MultibodyPlant method overloads that use an internal default for model instance will lead to sadness later, when users want to compose models by (for example) reading the same model file twice into a plant with different model names (see Parser() model_name_prefix overload, Parser::SetAutoRenaming(), etc.).

The consequences of the current implementation are easy to see with some test like:

TEST_F(UsdParserTest, TwiceTest) {                                             |                                                                                                                                   
  std::string filename = FindUsdTestResourceOrThrow("simple_geometries.usda"); |                                                                                                                                   
  ParseFile(filename);                                                         |                                                                                                                                   
  ParseFile(filename);                                                         |                                                                                                                                   
}         

A more likely scenario is a Drake dmd.yaml file that wants to place multiple arms, manipulable objects, etc., in a scene by repeatedly loading usda files with different model names and weld points.

For Parser() level examples, see detail_parser_test.cc.


multibody/parsing/detail_usd_parser.cc line 259 at r4 (raw file):

  // Returning an empty vector, since only rigidbody colliders are supported
  // at the moment (i.e., no actual models are involved).
  return std::vector<ModelInstanceIndex>();

Probably somewhere around the beginning of this function is where a parser would typically add a model instance, and then make it available to the parser methods that need it. I suspect usda will be closer to URDF (just read everything into one model), than SDFormat (fully realized language for nested models, file inclusion, etc., etc.).

Making the model typically looks something like this:

multibody/parsing/detail_urdf_parser.cc:    model_name = MakeModelName(model_name, parent_model_name_, w_);
multibody/parsing/detail_urdf_parser.cc-    model_instance_ = w_.plant->AddModelInstance(model_name);

Note that model instances don't have any rigid body topology or physics consequences; they are mostly important for naming and model composition into a single plant.


multibody/parsing/test/detail_usd_parser_test.cc line 60 at r4 (raw file):

  ParseFile(filename);

  DRAKE_ASSERT(plant_.num_bodies() == 5);

Using DRAKE_ASSERT here will do one of two things:

  • in debug builds, blow up the test program and probably give worse diagnostic output than other choices.
  • in release builds, do nothing.

We can use the gtest idiomatic clauses here:

EXPECT_EQ(plant_.num_bodies(), 5);

etc.


multibody/parsing/test/usd_parser_test/simple_geometries.usda line 1 at r4 (raw file):

#usda 1.0

question: what docs should I be reading to get the "user/authoring view" of usda format files?

Copy link
Author

@hong-nvidia hong-nvidia left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Reviewable status: 5 unresolved discussions, LGTM missing from assignee rpoyner-tri(platform), needs at least two assigned reviewers, commits need curation (https://drake.mit.edu/reviewable.html#curated-commits)


multibody/parsing/detail_usd_geometry.cc line 61 at r1 (raw file):

Previously, rpoyner-tri (Rick Poyner (rico)) wrote…

Hm. If I understand the interface, we have no way of distinguishing "the input didn't have a value" from "the programmer chose the wrong data type". In that case, we (at least) need a unit test case to demonstrate parsing of a mass value other than the default.

Looking deeper into OpenUSD, there is a whole run-time type system (attribute->GetType(), etc.) we could interrogate. One could imagine writing a DRAKE_ASSERT to verify we picked the right type. Failure of the assert would be more precise, but would not remove the need for the end-to-end non-default value reading test. Depending on how awkward it is to write, it may not be worth it.

The current test file simple_geometries.usda contains four RigidBody prims, which all have the physics:mass attribute with different values. Successfully parsing that file should demonstrate the parsing of mass values other than the default, right?

Regarding differentiating between "the programmer chose the wrong data type" and "the attribute does not have a value", here are my thoughts. In USD, the programmer doesn't usually have a chance to choose the wrong data type. For example, let's say that I want to create a mass attribute for my RigidBody prim (in case you're not familiar with USD terminologies, a prim is a basic object/entity in the scene), I need to do the following:

UsdStage stage = UsdStage::Open(my_filename);
UsdPrim my_rigidbody_prim = stage->GetPrimAtPath("/World/RigidBodyBox");
UsdPhysicsMassAPI prim_mass_api = UsdPhysicsMassAPI(my_rigidbody_prim);
UsdAttribute mass_attribute = prim_mass_api.CreateMassAttr();
mass_attribute.Set(3.0);
stage.Export("result.usda");

After that, if we look at the generated result.usda file, you'll see a line that says this under the prim

float physics:mass = 3

In the above example, the programmer doesn't get to choose the type of the attribute, so it's not possible to author an attribute with invalid type. (Note that there are attributes, such as the translate of a prim, where you can specify the precision of the type).

To be fair, there is a way to create attributes of the wrong type. We can do something like the following:

my_rigidbody_prim.CreateAttribute("physics:mass", UsdType::Double).Set(3.0);

And the resulting attribute in the USDA file would look like this:

double physics:mass = 3

And that would give us trouble when we try to read the value of the mass through GetMassAttr().Get(), since the USD library assumes that physics:mass is a float type. Creating an attribute in a raw way, like what we did above, is considered bad practice as we are hardcoding the name of the attribute as well as the type, which allows room for error. Authoring raw attribute is generally discouraged when formal APIs like CreateMassAttr() and GetMassAttr() are available.

So overall, I don't think we need to differentiate between "the programmer chose the wrong data type" and "the attribute does not have a value", since the former is unlikely if the author of the file uses USD properly.


multibody/parsing/detail_usd_parser.cc line 161 at r4 (raw file):

Previously, rpoyner-tri (Rick Poyner (rico)) wrote…

Using MultibodyPlant method overloads that use an internal default for model instance will lead to sadness later, when users want to compose models by (for example) reading the same model file twice into a plant with different model names (see Parser() model_name_prefix overload, Parser::SetAutoRenaming(), etc.).

The consequences of the current implementation are easy to see with some test like:

TEST_F(UsdParserTest, TwiceTest) {                                             |                                                                                                                                   
  std::string filename = FindUsdTestResourceOrThrow("simple_geometries.usda"); |                                                                                                                                   
  ParseFile(filename);                                                         |                                                                                                                                   
  ParseFile(filename);                                                         |                                                                                                                                   
}         

A more likely scenario is a Drake dmd.yaml file that wants to place multiple arms, manipulable objects, etc., in a scene by repeatedly loading usda files with different model names and weld points.

For Parser() level examples, see detail_parser_test.cc.

Fixed. Thanks for pointing that out.


multibody/parsing/detail_usd_parser.cc line 259 at r4 (raw file):

Previously, rpoyner-tri (Rick Poyner (rico)) wrote…

Probably somewhere around the beginning of this function is where a parser would typically add a model instance, and then make it available to the parser methods that need it. I suspect usda will be closer to URDF (just read everything into one model), than SDFormat (fully realized language for nested models, file inclusion, etc., etc.).

Making the model typically looks something like this:

multibody/parsing/detail_urdf_parser.cc:    model_name = MakeModelName(model_name, parent_model_name_, w_);
multibody/parsing/detail_urdf_parser.cc-    model_instance_ = w_.plant->AddModelInstance(model_name);

Note that model instances don't have any rigid body topology or physics consequences; they are mostly important for naming and model composition into a single plant.

Done.


multibody/parsing/test/detail_usd_parser_test.cc line 60 at r4 (raw file):

Previously, rpoyner-tri (Rick Poyner (rico)) wrote…

Using DRAKE_ASSERT here will do one of two things:

  • in debug builds, blow up the test program and probably give worse diagnostic output than other choices.
  • in release builds, do nothing.

We can use the gtest idiomatic clauses here:

EXPECT_EQ(plant_.num_bodies(), 5);

etc.

Done.

Copy link
Author

@hong-nvidia hong-nvidia left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Reviewable status: 5 unresolved discussions, LGTM missing from assignee rpoyner-tri(platform), needs at least two assigned reviewers, commits need curation (https://drake.mit.edu/reviewable.html#curated-commits) (waiting on @hong-nvidia)


multibody/parsing/test/usd_parser_test/simple_geometries.usda line 1 at r4 (raw file):

Previously, rpoyner-tri (Rick Poyner (rico)) wrote…

question: what docs should I be reading to get the "user/authoring view" of usda format files?

I assume you're asking about how one should go about authoring/reading an USD/USDA file (let me know if that's not the case).
In USD, the syntax and grammar of the file format are abstracted away from the authors and the users. One only needs to interact with the USD library. For example, I can author an USD file like this (these are high-level pseudocode):

stage = UsdStage::CreateInMemory()
stage_metadata = stage.GetMetadata()
stage_metadata.Set("upAxis", "Z")
mesh_prim = stage.DefineMeshPrim(prim_path="/World/MyMesh")
mesh_prim.SetMeshVertices(...)
mesh_prim.SetMeshIndices(...)
mesh_prim.transform.SetTranslate(translate=Vec3(0, 5, 0))
// ... Do other things to the stage ...
// Finally, write the resulting scene/stage to a file
stage.Export("my_stage.usd") // binary version
stage.Export("my_stage.usda") // human-readable version

To use an USD file, we simply open the stage and use it to query information:

stage = UsdStage::Open("my_stage.usd")
mesh_prim = stage.GetPrimAtPath(prim_path="/World/MyMesh")
mesh_num_vertices = mesh_prim.GetMeshVertices().size()
for prim in stage.Traverse() { // traverse every prim in the tree of the stage
    // ... Do something with the prim ...
}
// ... Do other things with the stage ...

Regarding the reading material, a good starting point would be the USD tutorial from the official website. That should give an overview of different concepts in USD and how one typically uses the library.

Copy link
Contributor

@rpoyner-tri rpoyner-tri left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Some responses. Still reading. Thanks for your patience!

Reviewed 1 of 2 files at r6, all commit messages.
Reviewable status: 1 unresolved discussion, LGTM missing from assignee rpoyner-tri(platform), needs at least two assigned reviewers, commits need curation (https://drake.mit.edu/reviewable.html#curated-commits) (waiting on @hong-nvidia)


multibody/parsing/detail_usd_geometry.cc line 61 at r1 (raw file):
I have full confidence that you will use USD properly. My concerns are

  • the next person, months or years from now, that has to maintain this code,
  • what happens if a revised physics schema turns up with mass as type double.

The current test file simple_geometries.usda contains four RigidBody prims, which all have the physics:mass attribute with different values. Successfully parsing that file should demonstrate the parsing > of mass values other than the default, right?

The current test shows that the Parse() call did not return an error-indicating return value, and shows that some bodies ended up in MultibodyPlant. Given that we also provide default values from parsing routines, the test would either have to show that the parsed value matched expectation, and/or assert things about warnings. Last time I tried the s/float/double/ experiment, the test still passed.

In any case, the end-to-end data flow test captures what we care about most. Having a cheap (either static or debug-only) assertion against the schema would be additional insurance, but like many insurance products, maybe not worth the premium.


multibody/parsing/test/usd_parser_test/simple_geometries.usda line 1 at r4 (raw file):

Previously, hong-nvidia wrote…

I assume you're asking about how one should go about authoring/reading an USD/USDA file (let me know if that's not the case).
In USD, the syntax and grammar of the file format are abstracted away from the authors and the users. One only needs to interact with the USD library. For example, I can author an USD file like this (these are high-level pseudocode):

stage = UsdStage::CreateInMemory()
stage_metadata = stage.GetMetadata()
stage_metadata.Set("upAxis", "Z")
mesh_prim = stage.DefineMeshPrim(prim_path="/World/MyMesh")
mesh_prim.SetMeshVertices(...)
mesh_prim.SetMeshIndices(...)
mesh_prim.transform.SetTranslate(translate=Vec3(0, 5, 0))
// ... Do other things to the stage ...
// Finally, write the resulting scene/stage to a file
stage.Export("my_stage.usd") // binary version
stage.Export("my_stage.usda") // human-readable version

To use an USD file, we simply open the stage and use it to query information:

stage = UsdStage::Open("my_stage.usd")
mesh_prim = stage.GetPrimAtPath(prim_path="/World/MyMesh")
mesh_num_vertices = mesh_prim.GetMeshVertices().size()
for prim in stage.Traverse() { // traverse every prim in the tree of the stage
    // ... Do something with the prim ...
}
// ... Do other things with the stage ...

Regarding the reading material, a good starting point would be the USD tutorial from the official website. That should give an overview of different concepts in USD and how one typically uses the library.

Thanks!

Copy link
Author

@hong-nvidia hong-nvidia left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Reviewable status: 1 unresolved discussion, LGTM missing from assignee rpoyner-tri(platform), needs at least two assigned reviewers, commits need curation (https://drake.mit.edu/reviewable.html#curated-commits)


multibody/parsing/detail_usd_geometry.cc line 61 at r1 (raw file):

Last time I tried the s/float/double/ experiment, the test still passed.

Hmm, the test is supposed to fail because of the triggered warning. Specifically, when I change the type of the mass attribute from float to double, or delete the value of the attribute, the test fails with the following message:

bazel-out/k8-opt/bin/common/test_utilities/_virtual_includes/diagnostic_policy_test_base/drake/common/test_utilities/diagnostic_policy_test_base.h:73: Failure
Value of: warning_records_.empty()
  Actual: false
Expected: true
warning: Failed to read the mass of the prim at /World/RigidBodyCapsule. Using the default value (1) instead

I'm not sure why the warning is not triggering on your side. Also, should we explicitly tell the DiagnosticPolicy to treat warning as errors? (looks like it's already doing this without me specifying)

Having a cheap (either static or debug-only) assertion against the schema would be additional insurance, but like many insurance products, maybe not worth the premium.

Agreed that this is a low-hanging fruit to get us insured. I just added a simple DRAKE_ASSERT that checks the type of the mass attribute.

Copy link
Contributor

@rpoyner-tri rpoyner-tri left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Reviewable status: LGTM missing from assignee rpoyner-tri(platform), needs at least two assigned reviewers, commits need curation (https://drake.mit.edu/reviewable.html#curated-commits) (waiting on @hong-nvidia)


multibody/parsing/detail_usd_geometry.cc line 61 at r1 (raw file):

Previously, hong-nvidia wrote…

Last time I tried the s/float/double/ experiment, the test still passed.

Hmm, the test is supposed to fail because of the triggered warning. Specifically, when I change the type of the mass attribute from float to double, or delete the value of the attribute, the test fails with the following message:

bazel-out/k8-opt/bin/common/test_utilities/_virtual_includes/diagnostic_policy_test_base/drake/common/test_utilities/diagnostic_policy_test_base.h:73: Failure
Value of: warning_records_.empty()
  Actual: false
Expected: true
warning: Failed to read the mass of the prim at /World/RigidBodyCapsule. Using the default value (1) instead

I'm not sure why the warning is not triggering on your side. Also, should we explicitly tell the DiagnosticPolicy to treat warning as errors? (looks like it's already doing this without me specifying)

Having a cheap (either static or debug-only) assertion against the schema would be additional insurance, but like many insurance products, maybe not worth the premium.

Agreed that this is a low-hanging fruit to get us insured. I just added a simple DRAKE_ASSERT that checks the type of the mass attribute.

Ah, excellent. I need to re-check why I did not see the warnings count trip in the test 🤦 Love the DRAKE_ASSERT here!

Copy link
Contributor

@rpoyner-tri rpoyner-tri left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Thanks for the updates. Still reading here, and still trying to study up on my OpenUSD.

At some point in the next few days, I'll try to share some test coverage results, and show you how to replicate them yourself (still requires an unmerged patch thanks to bazel version updates).

Reviewable status: LGTM missing from assignee rpoyner-tri(platform), needs at least two assigned reviewers, commits need curation (https://drake.mit.edu/reviewable.html#curated-commits) (waiting on @hong-nvidia)

Copy link
Contributor

@rpoyner-tri rpoyner-tri left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Reviewable status: 1 unresolved discussion, LGTM missing from assignee rpoyner-tri(platform), needs at least two assigned reviewers, commits need curation (https://drake.mit.edu/reviewable.html#curated-commits) (waiting on @hong-nvidia)

a discussion (no related file):
About test coverage.

From my bash history, something like this:

#  Cherry pick a patch that fixes coverage data handling in newer bazel, from #21188. I hope this merges soon, but who knows.
 2001  git cherry-pick pr21188
# Run tests I care about, with kcov configuration
 2002  bazel test --config=kcov //multibody/parsing/...
# Slurp the coverage data out of bazel output dirs into a new directory
 2003  ./tools/dynamic_analysis/kcov_tool merge ~/tmp/kcov-pr21405
# Open the coverage html index in a browser
 2004  see ~/tmp/kcov-pr21405/index.html & disown
# Oops, forgot to say WITH_USD=ON
 2005  bazel test --config=kcov --define=WITH_USD=ON //multibody/parsing/...
# Merge in some more coverage data into the previous data.c
 2006  ./tools/dynamic_analysis/kcov_tool merge ~/tmp/kcov-pr21405

Drake official doc talks about kcov at the bottom of this page: https://drake.mit.edu/bazel.html

Practical tips:

  • kcov test runs are slow, because no cached test results are honored, and the build is effectively a debug build. So, all your tests run at their slowest.
  • to cope with this, I usually do the coverage measurements I want, and then locally sprinkle doomed assertions (usually DRAKE_DEMAND(false)) into the uncovered code paths. Once that is done I can iterate (with regular build settings) over writing tests that reach the doom assertions, remove them, and repeat until all the doom-assertions are gone.

Copy link
Contributor

@rpoyner-tri rpoyner-tri left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Reviewable status: 2 unresolved discussions, LGTM missing from assignee rpoyner-tri(platform), needs at least two assigned reviewers, commits need curation (https://drake.mit.edu/reviewable.html#curated-commits) (waiting on @hong-nvidia)

a discussion (no related file):
The above thread is "coverage: what and how", this thread is "coverage: why".

In our experience working with Drake users, we have found that good parser diagnostics are key to avoiding time wasted debugging some problem arising from silently ignored data, typos, etc. Much of this is a result of the design choices of URDF and SDFormat, namely, that humans should hand-write XML. My hope is that USD will be much less prone to that, given the schemas, tools, and idioms in place. Still, we want to make sure that our parsing diagnostics are good, since I suspect roboticists will not be able to resist the temptation to hand-edit usda model files.

I don't know that there is a specific action item here for this PR. The long term goal I wish to converge on, is something like:

Every item in a model file has one (or more??) of the following results:

  • it ends up in data inside MultibodyPlant or SceneGraph.
  • it causes the parser to emit a warning or an error.
  • it is silently ignored, and this behavior is documented.

In the short run, I would like to make sure we test the paths with diagnostic policy warnings and errors. The paths that are bare throw or assertions should either be unreachable by bad input, or implementation firewalls ("not yet implemented").

Note that the long term goal is still a work in progress for existing parsers as well.


Copy link
Author

@hong-nvidia hong-nvidia left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Reviewable status: 2 unresolved discussions, LGTM missing from assignee rpoyner-tri(platform), needs at least two assigned reviewers, commits need curation (https://drake.mit.edu/reviewable.html#curated-commits)

a discussion (no related file):

Previously, rpoyner-tri (Rick Poyner (rico)) wrote…

The above thread is "coverage: what and how", this thread is "coverage: why".

In our experience working with Drake users, we have found that good parser diagnostics are key to avoiding time wasted debugging some problem arising from silently ignored data, typos, etc. Much of this is a result of the design choices of URDF and SDFormat, namely, that humans should hand-write XML. My hope is that USD will be much less prone to that, given the schemas, tools, and idioms in place. Still, we want to make sure that our parsing diagnostics are good, since I suspect roboticists will not be able to resist the temptation to hand-edit usda model files.

I don't know that there is a specific action item here for this PR. The long term goal I wish to converge on, is something like:

Every item in a model file has one (or more??) of the following results:

  • it ends up in data inside MultibodyPlant or SceneGraph.
  • it causes the parser to emit a warning or an error.
  • it is silently ignored, and this behavior is documented.

In the short run, I would like to make sure we test the paths with diagnostic policy warnings and errors. The paths that are bare throw or assertions should either be unreachable by bad input, or implementation firewalls ("not yet implemented").

Note that the long term goal is still a work in progress for existing parsers as well.

Understood. I added a handful of other tests, which covered most of the code paths with diagnostic warnings and errors.


Copy link
Contributor

@rpoyner-tri rpoyner-tri left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Thanks for updates! Things are definitely moving the right direction, but still a ways to go. I've raised some more stuff, and probably can help with some of it. I'll be around the rest of this week, then on vacation all of Memorial Day week. See you after that, if not before.

Thanks for you patience!

Reviewed 1 of 2 files at r4, 6 of 9 files at r8, all commit messages.
Reviewable status: 8 unresolved discussions, LGTM missing from assignee rpoyner-tri(platform), needs at least two assigned reviewers, commits need curation (https://drake.mit.edu/reviewable.html#curated-commits) (waiting on @hong-nvidia)

a discussion (no related file):

Previously, hong-nvidia wrote…

Understood. I added a handful of other tests, which covered most of the code paths with diagnostic warnings and errors.

Thanks!


a discussion (no related file):
I'm going to propose a little additional patch, that will allow us to feed files directly into the parser, and feel a version of the "end user experience".

diff --git a/multibody/parsing/BUILD.bazel b/multibody/parsing/BUILD.bazel
index fe18bf9376..c84b8e5bbd 100644
--- a/multibody/parsing/BUILD.bazel
+++ b/multibody/parsing/BUILD.bazel
@@ -360,6 +360,7 @@ drake_cc_library(
         ":detail_parsing_workspace",
         ":detail_sdf_parser",
         ":detail_urdf_parser",
+        ":detail_usd_parser",
     ],
 )
 
diff --git a/multibody/parsing/detail_select_parser.cc b/multibody/parsing/detail_select_parser.cc
index d99047859c..d1fe3fc37b 100644
--- a/multibody/parsing/detail_select_parser.cc
+++ b/multibody/parsing/detail_select_parser.cc
@@ -9,6 +9,7 @@
 #include "drake/multibody/parsing/detail_mujoco_parser.h"
 #include "drake/multibody/parsing/detail_sdf_parser.h"
 #include "drake/multibody/parsing/detail_urdf_parser.h"
+#include "drake/multibody/parsing/detail_usd_parser.h"
 
 namespace drake {
 namespace multibody {
@@ -18,7 +19,7 @@ using drake::internal::DiagnosticPolicy;
 
 namespace {
 
-enum class FileType { kUnknown, kSdf, kUrdf, kMjcf, kDmd, kMesh };
+enum class FileType { kUnknown, kSdf, kUrdf, kMjcf, kDmd, kMesh, kUsd };
 FileType DetermineFileType(const DiagnosticPolicy& policy,
                            const std::string& filename) {
   if (EndsWithCaseInsensitive(filename, ".urdf")) {
@@ -36,6 +37,10 @@ FileType DetermineFileType(const DiagnosticPolicy& policy,
   if (EndsWithCaseInsensitive(filename, ".obj")) {
     return FileType::kMesh;
   }
+  if (EndsWithCaseInsensitive(filename, ".usda") ||
+      EndsWithCaseInsensitive(filename, ".usd")) {
+    return FileType::kUsd;
+  }
   policy.Error(fmt::format(
       "The file '{}' is not a recognized type."
       " Known types are: .urdf, .sdf, .xml (Mujoco), .dmd.yaml, .obj",
@@ -70,6 +75,7 @@ ParserInterface& SelectParser(const DiagnosticPolicy& policy,
   static never_destroyed<internal::UnknownParserWrapper> unknown;
   static never_destroyed<internal::DmdParserWrapper> dmd;
   static never_destroyed<internal::MeshParserWrapper> mesh;
+  static never_destroyed<internal::UsdParserWrapper> usd;
   const FileType type = DetermineFileType(policy, filename);
   switch (type) {
     case FileType::kUrdf:
@@ -82,6 +88,8 @@ ParserInterface& SelectParser(const DiagnosticPolicy& policy,
       return dmd.access();
     case FileType::kMesh:
       return mesh.access();
+    case FileType::kUsd:
+      return usd.access();
     case FileType::kUnknown:
       return unknown.access();
   }

With the above in place, you can experiment directly with your parser, via parser_manual_test. I think the result for WITH_USD no on is acceptable for now (compare with error for some other file extension):

rico@PUGET-255560:~/checkout/drake3$ ./bazel-bin/multibody/parsing/parser_manual_test multibody/parsing/test/usd_parser_test/invalid/unsupported_geometry.usda 
parsing multibody/parsing/test/usd_parser_test/invalid/unsupported_geometry.usda
UsdParser is not available because WITH_USD is not ON
rico@PUGET-255560:~/checkout/drake3$ ./bazel-bin/multibody/parsing/parser_manual_test multibody/parsing/test/usd_parser_test/invalid/unsupported_geometry.usd
parsing multibody/parsing/test/usd_parser_test/invalid/unsupported_geometry.usd
UsdParser is not available because WITH_USD is not ON
rico@PUGET-255560:~/checkout/drake3$ ./bazel-bin/multibody/parsing/parser_manual_test multibody/parsing/test/usd_parser_test/invalid/unsupported_geometry.unknown
parsing multibody/parsing/test/usd_parser_test/invalid/unsupported_geometry.unknown
error: The file 'multibody/parsing/test/usd_parser_test/invalid/unsupported_geometry.unknown' is not a recognized type. Known types are: .urdf, .sdf, .xml (Mujoco), .dmd.yaml, .obj

When WITH_USD=ON, we can start pondering the quality of our parser output (and whether we have control of it?):

rico@PUGET-255560:~/checkout/drake3$ ./bazel-bin/multibody/parsing/parser_manual_test multibody/parsing/test/usd_parser_test/invalid/unsupported_geometry.usda 
parsing multibody/parsing/test/usd_parser_test/invalid/unsupported_geometry.usda
Processing /World
Warning: in _GetGeneratedSchema at line 783 of external/openusd_internal/pxr/usd/usd/schemaRegistry.cpp -- Failed to open schema layer at path '/home/rico/.cache/bazel/_bazel_rico/15ff2e144c7e926083749497375aafc7/execroot/drake/bazel-out/k8-opt/bin/multibody/parsing/parser_manual_test.runfiles/openusd_internal/pxr/usd/usd/@PLUG_INFO_ROOT@/@PLUG_INFO_RESOURCE_PATH@/generatedSchema.usda'. Any schemas defined in plugin library 'usd' will not have valid prim definitions.
Warning (secondary thread): in _GetGeneratedSchema at line 783 of external/openusd_internal/pxr/usd/usd/schemaRegistry.cpp -- Failed to open schema layer at path '/home/rico/.cache/bazel/_bazel_rico/15ff2e144c7e926083749497375aafc7/execroot/drake/bazel-out/k8-opt/bin/multibody/parsing/parser_manual_test.runfiles/openusd_internal/pxr/usd/usdGeom/@PLUG_INFO_ROOT@/@PLUG_INFO_RESOURCE_PATH@/generatedSchema.usda'. Any schemas defined in plugin library 'usdGeom' will not have valid prim definitions.
Warning (secondary thread): in _GetGeneratedSchema at line 783 of external/openusd_internal/pxr/usd/usd/schemaRegistry.cpp -- Failed to open schema layer at path '/home/rico/.cache/bazel/_bazel_rico/15ff2e144c7e926083749497375aafc7/execroot/drake/bazel-out/k8-opt/bin/multibody/parsing/parser_manual_test.runfiles/openusd_internal/pxr/usd/usdShade/@PLUG_INFO_ROOT@/@PLUG_INFO_RESOURCE_PATH@/generatedSchema.usda'. Any schemas defined in plugin library 'usdShade' will not have valid prim definitions.
Warning (secondary thread): in _GetGeneratedSchema at line 783 of external/openusd_internal/pxr/usd/usd/schemaRegistry.cpp -- Failed to open schema layer at path '/home/rico/.cache/bazel/_bazel_rico/15ff2e144c7e926083749497375aafc7/execroot/drake/bazel-out/k8-opt/bin/multibody/parsing/parser_manual_test.runfiles/openusd_internal/pxr/usd/usdPhysics/@PLUG_INFO_ROOT@/@PLUG_INFO_RESOURCE_PATH@/generatedSchema.usda'. Any schemas defined in plugin library 'usdPhysics' will not have valid prim definitions.
Warning: in _MapSchematicsPropertyPaths at line 198 of external/openusd_internal/pxr/usd/usd/primDefinition.cpp -- No prim spec exists at path '/PhysicsRigidBodyAPI' in schematics layer anon:0x7510d40022c0:/home/rico/.cache/bazel/_bazel_rico/15ff2e144c7e926083749497375aafc7/execroot/drake/bazel-out/k8-opt/bin/multibody/parsing/parser_manual_test.runfiles/openusd_internal/pxr/usd/usdPhysics/@PLUG_INFO_ROOT@/@PLUG_INFO_RESOURCE_PATH@/generatedSchema.usda.
Warning: in _MapSchematicsPropertyPaths at line 198 of external/openusd_internal/pxr/usd/usd/primDefinition.cpp -- No prim spec exists at path '/MotionAPI' in schematics layer anon:0x7510e8001b90:/home/rico/.cache/bazel/_bazel_rico/15ff2e144c7e926083749497375aafc7/execroot/drake/bazel-out/k8-opt/bin/multibody/parsing/parser_manual_test.runfiles/openusd_internal/pxr/usd/usdGeom/@PLUG_INFO_ROOT@/@PLUG_INFO_RESOURCE_PATH@/generatedSchema.usda.
Warning: in _MapSchematicsPropertyPaths at line 198 of external/openusd_internal/pxr/usd/usd/primDefinition.cpp -- No prim spec exists at path '/CoordSysAPI' in schematics layer anon:0x751008001520:/home/rico/.cache/bazel/_bazel_rico/15ff2e144c7e926083749497375aafc7/execroot/drake/bazel-out/k8-opt/bin/multibody/parsing/parser_manual_test.runfiles/openusd_internal/pxr/usd/usdShade/@PLUG_INFO_ROOT@/@PLUG_INFO_RESOURCE_PATH@/generatedSchema.usda.
Warning: in _MapSchematicsPropertyPaths at line 198 of external/openusd_internal/pxr/usd/usd/primDefinition.cpp -- No prim spec exists at path '/PhysicsMeshCollisionAPI' in schematics layer anon:0x7510d40022c0:/home/rico/.cache/bazel/_bazel_rico/15ff2e144c7e926083749497375aafc7/execroot/drake/bazel-out/k8-opt/bin/multibody/parsing/parser_manual_test.runfiles/openusd_internal/pxr/usd/usdPhysics/@PLUG_INFO_ROOT@/@PLUG_INFO_RESOURCE_PATH@/generatedSchema.usda.
Warning: in _MapSchematicsPropertyPaths at line 198 of external/openusd_internal/pxr/usd/usd/primDefinition.cpp -- No prim spec exists at path '/PhysicsFilteredPairsAPI' in schematics layer anon:0x7510d40022c0:/home/rico/.cache/bazel/_bazel_rico/15ff2e144c7e926083749497375aafc7/execroot/drake/bazel-out/k8-opt/bin/multibody/parsing/parser_manual_test.runfiles/openusd_internal/pxr/usd/usdPhysics/@PLUG_INFO_ROOT@/@PLUG_INFO_RESOURCE_PATH@/generatedSchema.usda.
Warning: in _MapSchematicsPropertyPaths at line 198 of external/openusd_internal/pxr/usd/usd/primDefinition.cpp -- No prim spec exists at path '/PhysicsMassAPI' in schematics layer anon:0x7510d40022c0:/home/rico/.cache/bazel/_bazel_rico/15ff2e144c7e926083749497375aafc7/execroot/drake/bazel-out/k8-opt/bin/multibody/parsing/parser_manual_test.runfiles/openusd_internal/pxr/usd/usdPhysics/@PLUG_INFO_ROOT@/@PLUG_INFO_RESOURCE_PATH@/generatedSchema.usda.
Warning: in _MapSchematicsPropertyPaths at line 198 of external/openusd_internal/pxr/usd/usd/primDefinition.cpp -- No prim spec exists at path '/PhysicsCollisionAPI' in schematics layer anon:0x7510d40022c0:/home/rico/.cache/bazel/_bazel_rico/15ff2e144c7e926083749497375aafc7/execroot/drake/bazel-out/k8-opt/bin/multibody/parsing/parser_manual_test.runfiles/openusd_internal/pxr/usd/usdPhysics/@PLUG_INFO_ROOT@/@PLUG_INFO_RESOURCE_PATH@/generatedSchema.usda.
Warning: in _MapSchematicsPropertyPaths at line 198 of external/openusd_internal/pxr/usd/usd/primDefinition.cpp -- No prim spec exists at path '/PhysicsLimitAPI' in schematics layer anon:0x7510d40022c0:/home/rico/.cache/bazel/_bazel_rico/15ff2e144c7e926083749497375aafc7/execroot/drake/bazel-out/k8-opt/bin/multibody/parsing/parser_manual_test.runfiles/openusd_internal/pxr/usd/usdPhysics/@PLUG_INFO_ROOT@/@PLUG_INFO_RESOURCE_PATH@/generatedSchema.usda.
Warning: in _MapSchematicsPropertyPaths at line 198 of external/openusd_internal/pxr/usd/usd/primDefinition.cpp -- No prim spec exists at path '/PhysicsMaterialAPI' in schematics layer anon:0x7510d40022c0:/home/rico/.cache/bazel/_bazel_rico/15ff2e144c7e926083749497375aafc7/execroot/drake/bazel-out/k8-opt/bin/multibody/parsing/parser_manual_test.runfiles/openusd_internal/pxr/usd/usdPhysics/@PLUG_INFO_ROOT@/@PLUG_INFO_RESOURCE_PATH@/generatedSchema.usda.
Warning: in _MapSchematicsPropertyPaths at line 198 of external/openusd_internal/pxr/usd/usd/primDefinition.cpp -- No prim spec exists at path '/VisibilityAPI' in schematics layer anon:0x7510e8001b90:/home/rico/.cache/bazel/_bazel_rico/15ff2e144c7e926083749497375aafc7/execroot/drake/bazel-out/k8-opt/bin/multibody/parsing/parser_manual_test.runfiles/openusd_internal/pxr/usd/usdGeom/@PLUG_INFO_ROOT@/@PLUG_INFO_RESOURCE_PATH@/generatedSchema.usda.
Warning: in _MapSchematicsPropertyPaths at line 198 of external/openusd_internal/pxr/usd/usd/primDefinition.cpp -- No prim spec exists at path '/CollectionAPI' in schematics layer anon:0x654f28c21a80:/home/rico/.cache/bazel/_bazel_rico/15ff2e144c7e926083749497375aafc7/execroot/drake/bazel-out/k8-opt/bin/multibody/parsing/parser_manual_test.runfiles/openusd_internal/pxr/usd/usd/@PLUG_INFO_ROOT@/@PLUG_INFO_RESOURCE_PATH@/generatedSchema.usda.
Warning: in _MapSchematicsPropertyPaths at line 198 of external/openusd_internal/pxr/usd/usd/primDefinition.cpp -- No prim spec exists at path '/PhysicsArticulationRootAPI' in schematics layer anon:0x7510d40022c0:/home/rico/.cache/bazel/_bazel_rico/15ff2e144c7e926083749497375aafc7/execroot/drake/bazel-out/k8-opt/bin/multibody/parsing/parser_manual_test.runfiles/openusd_internal/pxr/usd/usdPhysics/@PLUG_INFO_ROOT@/@PLUG_INFO_RESOURCE_PATH@/generatedSchema.usda.
Warning: in _MapSchematicsPropertyPaths at line 198 of external/openusd_internal/pxr/usd/usd/primDefinition.cpp -- No prim spec exists at path '/NodeDefAPI' in schematics layer anon:0x751008001520:/home/rico/.cache/bazel/_bazel_rico/15ff2e144c7e926083749497375aafc7/execroot/drake/bazel-out/k8-opt/bin/multibody/parsing/parser_manual_test.runfiles/openusd_internal/pxr/usd/usdShade/@PLUG_INFO_ROOT@/@PLUG_INFO_RESOURCE_PATH@/generatedSchema.usda.
Warning: in _MapSchematicsPropertyPaths at line 198 of external/openusd_internal/pxr/usd/usd/primDefinition.cpp -- No prim spec exists at path '/PhysicsDriveAPI' in schematics layer anon:0x7510d40022c0:/home/rico/.cache/bazel/_bazel_rico/15ff2e144c7e926083749497375aafc7/execroot/drake/bazel-out/k8-opt/bin/multibody/parsing/parser_manual_test.runfiles/openusd_internal/pxr/usd/usdPhysics/@PLUG_INFO_ROOT@/@PLUG_INFO_RESOURCE_PATH@/generatedSchema.usda.
Warning: in _MapSchematicsPropertyPaths at line 198 of external/openusd_internal/pxr/usd/usd/primDefinition.cpp -- No prim spec exists at path '/MaterialBindingAPI' in schematics layer anon:0x751008001520:/home/rico/.cache/bazel/_bazel_rico/15ff2e144c7e926083749497375aafc7/execroot/drake/bazel-out/k8-opt/bin/multibody/parsing/parser_manual_test.runfiles/openusd_internal/pxr/usd/usdShade/@PLUG_INFO_ROOT@/@PLUG_INFO_RESOURCE_PATH@/generatedSchema.usda.
Warning: in _MapSchematicsPropertyPaths at line 198 of external/openusd_internal/pxr/usd/usd/primDefinition.cpp -- No prim spec exists at path '/GeomModelAPI' in schematics layer anon:0x7510e8001b90:/home/rico/.cache/bazel/_bazel_rico/15ff2e144c7e926083749497375aafc7/execroot/drake/bazel-out/k8-opt/bin/multibody/parsing/parser_manual_test.runfiles/openusd_internal/pxr/usd/usdGeom/@PLUG_INFO_ROOT@/@PLUG_INFO_RESOURCE_PATH@/generatedSchema.usda.
Warning: in _MapSchematicsPropertyPaths at line 198 of external/openusd_internal/pxr/usd/usd/primDefinition.cpp -- No prim spec exists at path '/Shader' in schematics layer anon:0x751008001520:/home/rico/.cache/bazel/_bazel_rico/15ff2e144c7e926083749497375aafc7/execroot/drake/bazel-out/k8-opt/bin/multibody/parsing/parser_manual_test.runfiles/openusd_internal/pxr/usd/usdShade/@PLUG_INFO_ROOT@/@PLUG_INFO_RESOURCE_PATH@/generatedSchema.usda.
Warning: in _MapSchematicsPropertyPaths at line 198 of external/openusd_internal/pxr/usd/usd/primDefinition.cpp -- No prim spec exists at path '/Material' in schematics layer anon:0x751008001520:/home/rico/.cache/bazel/_bazel_rico/15ff2e144c7e926083749497375aafc7/execroot/drake/bazel-out/k8-opt/bin/multibody/parsing/parser_manual_test.runfiles/openusd_internal/pxr/usd/usdShade/@PLUG_INFO_ROOT@/@PLUG_INFO_RESOURCE_PATH@/generatedSchema.usda.
Warning: in _MapSchematicsPropertyPaths at line 198 of external/openusd_internal/pxr/usd/usd/primDefinition.cpp -- No prim spec exists at path '/Capsule' in schematics layer anon:0x7510e8001b90:/home/rico/.cache/bazel/_bazel_rico/15ff2e144c7e926083749497375aafc7/execroot/drake/bazel-out/k8-opt/bin/multibody/parsing/parser_manual_test.runfiles/openusd_internal/pxr/usd/usdGeom/@PLUG_INFO_ROOT@/@PLUG_INFO_RESOURCE_PATH@/generatedSchema.usda.
Warning: in _MapSchematicsPropertyPaths at line 198 of external/openusd_internal/pxr/usd/usd/primDefinition.cpp -- No prim spec exists at path '/Mesh' in schematics layer anon:0x7510e8001b90:/home/rico/.cache/bazel/_bazel_rico/15ff2e144c7e926083749497375aafc7/execroot/drake/bazel-out/k8-opt/bin/multibody/parsing/parser_manual_test.runfiles/openusd_internal/pxr/usd/usdGeom/@PLUG_INFO_ROOT@/@PLUG_INFO_RESOURCE_PATH@/generatedSchema.usda.
Warning: in _MapSchematicsPropertyPaths at line 198 of external/openusd_internal/pxr/usd/usd/primDefinition.cpp -- No prim spec exists at path '/PhysicsScene' in schematics layer anon:0x7510d40022c0:/home/rico/.cache/bazel/_bazel_rico/15ff2e144c7e926083749497375aafc7/execroot/drake/bazel-out/k8-opt/bin/multibody/parsing/parser_manual_test.runfiles/openusd_internal/pxr/usd/usdPhysics/@PLUG_INFO_ROOT@/@PLUG_INFO_RESOURCE_PATH@/generatedSchema.usda.
Warning: in _MapSchematicsPropertyPaths at line 198 of external/openusd_internal/pxr/usd/usd/primDefinition.cpp -- No prim spec exists at path '/PhysicsRevoluteJoint' in schematics layer anon:0x7510d40022c0:/home/rico/.cache/bazel/_bazel_rico/15ff2e144c7e926083749497375aafc7/execroot/drake/bazel-out/k8-opt/bin/multibody/parsing/parser_manual_test.runfiles/openusd_internal/pxr/usd/usdPhysics/@PLUG_INFO_ROOT@/@PLUG_INFO_RESOURCE_PATH@/generatedSchema.usda.
Warning: in _MapSchematicsPropertyPaths at line 198 of external/openusd_internal/pxr/usd/usd/primDefinition.cpp -- No prim spec exists at path '/PhysicsJoint' in schematics layer anon:0x7510d40022c0:/home/rico/.cache/bazel/_bazel_rico/15ff2e144c7e926083749497375aafc7/execroot/drake/bazel-out/k8-opt/bin/multibody/parsing/parser_manual_test.runfiles/openusd_internal/pxr/usd/usdPhysics/@PLUG_INFO_ROOT@/@PLUG_INFO_RESOURCE_PATH@/generatedSchema.usda.
Warning: in _MapSchematicsPropertyPaths at line 198 of external/openusd_internal/pxr/usd/usd/primDefinition.cpp -- No prim spec exists at path '/PhysicsPrismaticJoint' in schematics layer anon:0x7510d40022c0:/home/rico/.cache/bazel/_bazel_rico/15ff2e144c7e926083749497375aafc7/execroot/drake/bazel-out/k8-opt/bin/multibody/parsing/parser_manual_test.runfiles/openusd_internal/pxr/usd/usdPhysics/@PLUG_INFO_ROOT@/@PLUG_INFO_RESOURCE_PATH@/generatedSchema.usda.
Warning: in _MapSchematicsPropertyPaths at line 198 of external/openusd_internal/pxr/usd/usd/primDefinition.cpp -- No prim spec exists at path '/NurbsCurves' in schematics layer anon:0x7510e8001b90:/home/rico/.cache/bazel/_bazel_rico/15ff2e144c7e926083749497375aafc7/execroot/drake/bazel-out/k8-opt/bin/multibody/parsing/parser_manual_test.runfiles/openusd_internal/pxr/usd/usdGeom/@PLUG_INFO_ROOT@/@PLUG_INFO_RESOURCE_PATH@/generatedSchema.usda.
Warning: in _MapSchematicsPropertyPaths at line 198 of external/openusd_internal/pxr/usd/usd/primDefinition.cpp -- No prim spec exists at path '/Xform' in schematics layer anon:0x7510e8001b90:/home/rico/.cache/bazel/_bazel_rico/15ff2e144c7e926083749497375aafc7/execroot/drake/bazel-out/k8-opt/bin/multibody/parsing/parser_manual_test.runfiles/openusd_internal/pxr/usd/usdGeom/@PLUG_INFO_ROOT@/@PLUG_INFO_RESOURCE_PATH@/generatedSchema.usda.
Warning: in _MapSchematicsPropertyPaths at line 198 of external/openusd_internal/pxr/usd/usd/primDefinition.cpp -- No prim spec exists at path '/NodeGraph' in schematics layer anon:0x751008001520:/home/rico/.cache/bazel/_bazel_rico/15ff2e144c7e926083749497375aafc7/execroot/drake/bazel-out/k8-opt/bin/multibody/parsing/parser_manual_test.runfiles/openusd_internal/pxr/usd/usdShade/@PLUG_INFO_ROOT@/@PLUG_INFO_RESOURCE_PATH@/generatedSchema.usda.
Warning: in _MapSchematicsPropertyPaths at line 198 of external/openusd_internal/pxr/usd/usd/primDefinition.cpp -- No prim spec exists at path '/Capsule_1' in schematics layer anon:0x7510e8001b90:/home/rico/.cache/bazel/_bazel_rico/15ff2e144c7e926083749497375aafc7/execroot/drake/bazel-out/k8-opt/bin/multibody/parsing/parser_manual_test.runfiles/openusd_internal/pxr/usd/usdGeom/@PLUG_INFO_ROOT@/@PLUG_INFO_RESOURCE_PATH@/generatedSchema.usda.
Warning: in _MapSchematicsPropertyPaths at line 198 of external/openusd_internal/pxr/usd/usd/primDefinition.cpp -- No prim spec exists at path '/Cylinder_1' in schematics layer anon:0x7510e8001b90:/home/rico/.cache/bazel/_bazel_rico/15ff2e144c7e926083749497375aafc7/execroot/drake/bazel-out/k8-opt/bin/multibody/parsing/parser_manual_test.runfiles/openusd_internal/pxr/usd/usdGeom/@PLUG_INFO_ROOT@/@PLUG_INFO_RESOURCE_PATH@/generatedSchema.usda.
Warning: in _MapSchematicsPropertyPaths at line 198 of external/openusd_internal/pxr/usd/usd/primDefinition.cpp -- No prim spec exists at path '/Cylinder' in schematics layer anon:0x7510e8001b90:/home/rico/.cache/bazel/_bazel_rico/15ff2e144c7e926083749497375aafc7/execroot/drake/bazel-out/k8-opt/bin/multibody/parsing/parser_manual_test.runfiles/openusd_internal/pxr/usd/usdGeom/@PLUG_INFO_ROOT@/@PLUG_INFO_RESOURCE_PATH@/generatedSchema.usda.
Warning: in _MapSchematicsPropertyPaths at line 198 of external/openusd_internal/pxr/usd/usd/primDefinition.cpp -- No prim spec exists at path '/PhysicsCollisionGroup' in schematics layer anon:0x7510d40022c0:/home/rico/.cache/bazel/_bazel_rico/15ff2e144c7e926083749497375aafc7/execroot/drake/bazel-out/k8-opt/bin/multibody/parsing/parser_manual_test.runfiles/openusd_internal/pxr/usd/usdPhysics/@PLUG_INFO_ROOT@/@PLUG_INFO_RESOURCE_PATH@/generatedSchema.usda.
Warning: in _MapSchematicsPropertyPaths at line 198 of external/openusd_internal/pxr/usd/usd/primDefinition.cpp -- No prim spec exists at path '/PhysicsFixedJoint' in schematics layer anon:0x7510d40022c0:/home/rico/.cache/bazel/_bazel_rico/15ff2e144c7e926083749497375aafc7/execroot/drake/bazel-out/k8-opt/bin/multibody/parsing/parser_manual_test.runfiles/openusd_internal/pxr/usd/usdPhysics/@PLUG_INFO_ROOT@/@PLUG_INFO_RESOURCE_PATH@/generatedSchema.usda.
Warning: in _MapSchematicsPropertyPaths at line 198 of external/openusd_internal/pxr/usd/usd/primDefinition.cpp -- No prim spec exists at path '/Plane' in schematics layer anon:0x7510e8001b90:/home/rico/.cache/bazel/_bazel_rico/15ff2e144c7e926083749497375aafc7/execroot/drake/bazel-out/k8-opt/bin/multibody/parsing/parser_manual_test.runfiles/openusd_internal/pxr/usd/usdGeom/@PLUG_INFO_ROOT@/@PLUG_INFO_RESOURCE_PATH@/generatedSchema.usda.
Warning: in _MapSchematicsPropertyPaths at line 198 of external/openusd_internal/pxr/usd/usd/primDefinition.cpp -- No prim spec exists at path '/PhysicsDistanceJoint' in schematics layer anon:0x7510d40022c0:/home/rico/.cache/bazel/_bazel_rico/15ff2e144c7e926083749497375aafc7/execroot/drake/bazel-out/k8-opt/bin/multibody/parsing/parser_manual_test.runfiles/openusd_internal/pxr/usd/usdPhysics/@PLUG_INFO_ROOT@/@PLUG_INFO_RESOURCE_PATH@/generatedSchema.usda.
Warning: in _MapSchematicsPropertyPaths at line 198 of external/openusd_internal/pxr/usd/usd/primDefinition.cpp -- No prim spec exists at path '/NurbsPatch' in schematics layer anon:0x7510e8001b90:/home/rico/.cache/bazel/_bazel_rico/15ff2e144c7e926083749497375aafc7/execroot/drake/bazel-out/k8-opt/bin/multibody/parsing/parser_manual_test.runfiles/openusd_internal/pxr/usd/usdGeom/@PLUG_INFO_ROOT@/@PLUG_INFO_RESOURCE_PATH@/generatedSchema.usda.
Warning: in _MapSchematicsPropertyPaths at line 198 of external/openusd_internal/pxr/usd/usd/primDefinition.cpp -- No prim spec exists at path '/BasisCurves' in schematics layer anon:0x7510e8001b90:/home/rico/.cache/bazel/_bazel_rico/15ff2e144c7e926083749497375aafc7/execroot/drake/bazel-out/k8-opt/bin/multibody/parsing/parser_manual_test.runfiles/openusd_internal/pxr/usd/usdGeom/@PLUG_INFO_ROOT@/@PLUG_INFO_RESOURCE_PATH@/generatedSchema.usda.
Warning: in _MapSchematicsPropertyPaths at line 198 of external/openusd_internal/pxr/usd/usd/primDefinition.cpp -- No prim spec exists at path '/PointInstancer' in schematics layer anon:0x7510e8001b90:/home/rico/.cache/bazel/_bazel_rico/15ff2e144c7e926083749497375aafc7/execroot/drake/bazel-out/k8-opt/bin/multibody/parsing/parser_manual_test.runfiles/openusd_internal/pxr/usd/usdGeom/@PLUG_INFO_ROOT@/@PLUG_INFO_RESOURCE_PATH@/generatedSchema.usda.
Warning: in _MapSchematicsPropertyPaths at line 198 of external/openusd_internal/pxr/usd/usd/primDefinition.cpp -- No prim spec exists at path '/Camera' in schematics layer anon:0x7510e8001b90:/home/rico/.cache/bazel/_bazel_rico/15ff2e144c7e926083749497375aafc7/execroot/drake/bazel-out/k8-opt/bin/multibody/parsing/parser_manual_test.runfiles/openusd_internal/pxr/usd/usdGeom/@PLUG_INFO_ROOT@/@PLUG_INFO_RESOURCE_PATH@/generatedSchema.usda.
Warning: in _MapSchematicsPropertyPaths at line 198 of external/openusd_internal/pxr/usd/usd/primDefinition.cpp -- No prim spec exists at path '/Cone' in schematics layer anon:0x7510e8001b90:/home/rico/.cache/bazel/_bazel_rico/15ff2e144c7e926083749497375aafc7/execroot/drake/bazel-out/k8-opt/bin/multibody/parsing/parser_manual_test.runfiles/openusd_internal/pxr/usd/usdGeom/@PLUG_INFO_ROOT@/@PLUG_INFO_RESOURCE_PATH@/generatedSchema.usda.
Warning: in _MapSchematicsPropertyPaths at line 198 of external/openusd_internal/pxr/usd/usd/primDefinition.cpp -- No prim spec exists at path '/Cube' in schematics layer anon:0x7510e8001b90:/home/rico/.cache/bazel/_bazel_rico/15ff2e144c7e926083749497375aafc7/execroot/drake/bazel-out/k8-opt/bin/multibody/parsing/parser_manual_test.runfiles/openusd_internal/pxr/usd/usdGeom/@PLUG_INFO_ROOT@/@PLUG_INFO_RESOURCE_PATH@/generatedSchema.usda.
Warning: in _MapSchematicsPropertyPaths at line 198 of external/openusd_internal/pxr/usd/usd/primDefinition.cpp -- No prim spec exists at path '/Sphere' in schematics layer anon:0x7510e8001b90:/home/rico/.cache/bazel/_bazel_rico/15ff2e144c7e926083749497375aafc7/execroot/drake/bazel-out/k8-opt/bin/multibody/parsing/parser_manual_test.runfiles/openusd_internal/pxr/usd/usdGeom/@PLUG_INFO_ROOT@/@PLUG_INFO_RESOURCE_PATH@/generatedSchema.usda.
Warning: in _MapSchematicsPropertyPaths at line 198 of external/openusd_internal/pxr/usd/usd/primDefinition.cpp -- No prim spec exists at path '/HermiteCurves' in schematics layer anon:0x7510e8001b90:/home/rico/.cache/bazel/_bazel_rico/15ff2e144c7e926083749497375aafc7/execroot/drake/bazel-out/k8-opt/bin/multibody/parsing/parser_manual_test.runfiles/openusd_internal/pxr/usd/usdGeom/@PLUG_INFO_ROOT@/@PLUG_INFO_RESOURCE_PATH@/generatedSchema.usda.
Warning: in _MapSchematicsPropertyPaths at line 198 of external/openusd_internal/pxr/usd/usd/primDefinition.cpp -- No prim spec exists at path '/Points' in schematics layer anon:0x7510e8001b90:/home/rico/.cache/bazel/_bazel_rico/15ff2e144c7e926083749497375aafc7/execroot/drake/bazel-out/k8-opt/bin/multibody/parsing/parser_manual_test.runfiles/openusd_internal/pxr/usd/usdGeom/@PLUG_INFO_ROOT@/@PLUG_INFO_RESOURCE_PATH@/generatedSchema.usda.
Warning: in _MapSchematicsPropertyPaths at line 198 of external/openusd_internal/pxr/usd/usd/primDefinition.cpp -- No prim spec exists at path '/Scope' in schematics layer anon:0x7510e8001b90:/home/rico/.cache/bazel/_bazel_rico/15ff2e144c7e926083749497375aafc7/execroot/drake/bazel-out/k8-opt/bin/multibody/parsing/parser_manual_test.runfiles/openusd_internal/pxr/usd/usdGeom/@PLUG_INFO_ROOT@/@PLUG_INFO_RESOURCE_PATH@/generatedSchema.usda.
Warning: in _MapSchematicsPropertyPaths at line 198 of external/openusd_internal/pxr/usd/usd/primDefinition.cpp -- No prim spec exists at path '/GeomSubset' in schematics layer anon:0x7510e8001b90:/home/rico/.cache/bazel/_bazel_rico/15ff2e144c7e926083749497375aafc7/execroot/drake/bazel-out/k8-opt/bin/multibody/parsing/parser_manual_test.runfiles/openusd_internal/pxr/usd/usdGeom/@PLUG_INFO_ROOT@/@PLUG_INFO_RESOURCE_PATH@/generatedSchema.usda.
Warning: in _MapSchematicsPropertyPaths at line 198 of external/openusd_internal/pxr/usd/usd/primDefinition.cpp -- No prim spec exists at path '/TetMesh' in schematics layer anon:0x7510e8001b90:/home/rico/.cache/bazel/_bazel_rico/15ff2e144c7e926083749497375aafc7/execroot/drake/bazel-out/k8-opt/bin/multibody/parsing/parser_manual_test.runfiles/openusd_internal/pxr/usd/usdGeom/@PLUG_INFO_ROOT@/@PLUG_INFO_RESOURCE_PATH@/generatedSchema.usda.
Warning: in _MapSchematicsPropertyPaths at line 198 of external/openusd_internal/pxr/usd/usd/primDefinition.cpp -- No prim spec exists at path '/PhysicsSphericalJoint' in schematics layer anon:0x7510d40022c0:/home/rico/.cache/bazel/_bazel_rico/15ff2e144c7e926083749497375aafc7/execroot/drake/bazel-out/k8-opt/bin/multibody/parsing/parser_manual_test.runfiles/openusd_internal/pxr/usd/usdPhysics/@PLUG_INFO_ROOT@/@PLUG_INFO_RESOURCE_PATH@/generatedSchema.usda.
Processing /World/Box
error: Unsupported Prim type: 

We are clearly getting a lot of spam from inside OpenUSD -- eventually (maybe not this PR) we will want to get control of that. It also looks like the diagnostic we generate is not yet very useful. It might be to early to demand file names and line numbers, but it looks like we are not even printing context we think we have.



multibody/parsing/detail_usd_geometry.h line 1 at r8 (raw file):

#include "drake/multibody/parsing/detail_common.h"

Module (detail_usd_geometry.{h,cc}) meta: there are a lot of cases uncovered by unit tests here. It will likely be worthwhile to write a direct unit test file for this module, though I'm fine to hold off until we feel like the function signature questions are settled.


multibody/parsing/detail_usd_geometry.h line 10 at r8 (raw file):

namespace internal {

// Returns the dimension of an UsdGeomCube as `Vector3d(length_x, length_y,

minor: to the extent that these functions provide hard-coded defaults for the nothing-in-input case, they should document the default values. I know some implementations are still in progress; we can skip those or use a // TODO(hong-nvidia) document default value. or similar.

Another alternative to consider for these parsing subroutines is to punt: have the return value be std::optional<Thing>, emit diagnostics when bad things happen, and then return an empty optional. Typically, the caller can then just return (or return its error return), to eventually end the parse.


multibody/parsing/detail_usd_geometry.h line 14 at r8 (raw file):

Eigen::Vector3d GetBoxDimension(
  const pxr::UsdPrim& prim, double meters_per_unit,
  const ParsingWorkspace& w);

minor The downside of just passing down ParsingWorkspace instead of passing a DiagnosticPolicy, is that we can't use a smarter subtype of DiagnosticPolicy to capture useful context, like input filename and source line. I'm not yet sure if we can get access to input file and line info from OpenUSD, but using the plain policy type at least keeps our options open.

For examples in other parsers, try grepping the parser sources for MakePolicyForNode(), and see input-aware types defined in multibody/parsing/detail_sdf_diagnostic.h and multibody/parsing/detail_tinyxml2_diagnostic.h.


multibody/parsing/detail_usd_geometry.h line 142 at r8 (raw file):

nit extra blank lines here. I'm surprised a drake linter didn't complain about this ;) .


multibody/parsing/detail_usd_geometry.cc line 167 at r8 (raw file):

      fmt::format("f {} {} {}\n", index0, index1, index2));
  }
  

nit trailing whitespace, here and some below.

Any chance you can configure your editor to automatically remove it?


multibody/parsing/detail_usd_parser.cc line 147 at r8 (raw file):

const RigidBody<double>& UsdParser::CreateRigidBody(const pxr::UsdPrim& prim) {
  double mpu = metadata_.meters_per_unit;
  SpatialInertia<double> si;

nit Eventually we are going to have to work through all of the https://drake.mit.edu/styleguide/cppguide.html stuff. I happened to show some of this code to a colleague, and he got very distracted by si as a variable name (we mostly disallow acronyms, unless there is some domain-specific reason). I suggest inertia here instead.

As for mpu, perhaps a case could be made for that one. I'm undecided so far about disallowing it, but meters_per_unit is strictly better.

There are probably other examples; I haven't gone through in detail.


multibody/parsing/detail_usd_parser.cc line 160 at r8 (raw file):

    si = SpatialInertia<double>::MakeUnitary();
  } else {
    si.SetNaN();

Generally we try not to create situations where NaNs will get fed into the physics engine; it leads to situations that are hard to debug. Since we are emitting an Error below anyway, probably best to drop this line.

Copy link
Author

@hong-nvidia hong-nvidia left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Thanks for the effort you're putting into reviewing this!

Reviewed 1 of 2 files at r4.
Reviewable status: 5 unresolved discussions, LGTM missing from assignee rpoyner-tri(platform), needs at least two assigned reviewers, commits need curation (https://drake.mit.edu/reviewable.html#curated-commits)


multibody/parsing/detail_usd_geometry.cc line 167 at r8 (raw file):

Previously, rpoyner-tri (Rick Poyner (rico)) wrote…

nit trailing whitespace, here and some below.

Any chance you can configure your editor to automatically remove it?

Got it


multibody/parsing/detail_usd_parser.cc line 147 at r8 (raw file):

Previously, rpoyner-tri (Rick Poyner (rico)) wrote…

nit Eventually we are going to have to work through all of the https://drake.mit.edu/styleguide/cppguide.html stuff. I happened to show some of this code to a colleague, and he got very distracted by si as a variable name (we mostly disallow acronyms, unless there is some domain-specific reason). I suggest inertia here instead.

As for mpu, perhaps a case could be made for that one. I'm undecided so far about disallowing it, but meters_per_unit is strictly better.

There are probably other examples; I haven't gone through in detail.

Agreed and fixed.


multibody/parsing/detail_usd_parser.cc line 160 at r8 (raw file):

Previously, rpoyner-tri (Rick Poyner (rico)) wrote…

Generally we try not to create situations where NaNs will get fed into the physics engine; it leads to situations that are hard to debug. Since we are emitting an Error below anyway, probably best to drop this line.

Done.

Copy link
Author

@hong-nvidia hong-nvidia left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Reviewable status: 4 unresolved discussions, LGTM missing from assignee rpoyner-tri(platform), needs at least two assigned reviewers, commits need curation (https://drake.mit.edu/reviewable.html#curated-commits)

a discussion (no related file):

Previously, rpoyner-tri (Rick Poyner (rico)) wrote…

I'm going to propose a little additional patch, that will allow us to feed files directly into the parser, and feel a version of the "end user experience".

diff --git a/multibody/parsing/BUILD.bazel b/multibody/parsing/BUILD.bazel
index fe18bf9376..c84b8e5bbd 100644
--- a/multibody/parsing/BUILD.bazel
+++ b/multibody/parsing/BUILD.bazel
@@ -360,6 +360,7 @@ drake_cc_library(
         ":detail_parsing_workspace",
         ":detail_sdf_parser",
         ":detail_urdf_parser",
+        ":detail_usd_parser",
     ],
 )
 
diff --git a/multibody/parsing/detail_select_parser.cc b/multibody/parsing/detail_select_parser.cc
index d99047859c..d1fe3fc37b 100644
--- a/multibody/parsing/detail_select_parser.cc
+++ b/multibody/parsing/detail_select_parser.cc
@@ -9,6 +9,7 @@
 #include "drake/multibody/parsing/detail_mujoco_parser.h"
 #include "drake/multibody/parsing/detail_sdf_parser.h"
 #include "drake/multibody/parsing/detail_urdf_parser.h"
+#include "drake/multibody/parsing/detail_usd_parser.h"
 
 namespace drake {
 namespace multibody {
@@ -18,7 +19,7 @@ using drake::internal::DiagnosticPolicy;
 
 namespace {
 
-enum class FileType { kUnknown, kSdf, kUrdf, kMjcf, kDmd, kMesh };
+enum class FileType { kUnknown, kSdf, kUrdf, kMjcf, kDmd, kMesh, kUsd };
 FileType DetermineFileType(const DiagnosticPolicy& policy,
                            const std::string& filename) {
   if (EndsWithCaseInsensitive(filename, ".urdf")) {
@@ -36,6 +37,10 @@ FileType DetermineFileType(const DiagnosticPolicy& policy,
   if (EndsWithCaseInsensitive(filename, ".obj")) {
     return FileType::kMesh;
   }
+  if (EndsWithCaseInsensitive(filename, ".usda") ||
+      EndsWithCaseInsensitive(filename, ".usd")) {
+    return FileType::kUsd;
+  }
   policy.Error(fmt::format(
       "The file '{}' is not a recognized type."
       " Known types are: .urdf, .sdf, .xml (Mujoco), .dmd.yaml, .obj",
@@ -70,6 +75,7 @@ ParserInterface& SelectParser(const DiagnosticPolicy& policy,
   static never_destroyed<internal::UnknownParserWrapper> unknown;
   static never_destroyed<internal::DmdParserWrapper> dmd;
   static never_destroyed<internal::MeshParserWrapper> mesh;
+  static never_destroyed<internal::UsdParserWrapper> usd;
   const FileType type = DetermineFileType(policy, filename);
   switch (type) {
     case FileType::kUrdf:
@@ -82,6 +88,8 @@ ParserInterface& SelectParser(const DiagnosticPolicy& policy,
       return dmd.access();
     case FileType::kMesh:
       return mesh.access();
+    case FileType::kUsd:
+      return usd.access();
     case FileType::kUnknown:
       return unknown.access();
   }

With the above in place, you can experiment directly with your parser, via parser_manual_test. I think the result for WITH_USD no on is acceptable for now (compare with error for some other file extension):

rico@PUGET-255560:~/checkout/drake3$ ./bazel-bin/multibody/parsing/parser_manual_test multibody/parsing/test/usd_parser_test/invalid/unsupported_geometry.usda 
parsing multibody/parsing/test/usd_parser_test/invalid/unsupported_geometry.usda
UsdParser is not available because WITH_USD is not ON
rico@PUGET-255560:~/checkout/drake3$ ./bazel-bin/multibody/parsing/parser_manual_test multibody/parsing/test/usd_parser_test/invalid/unsupported_geometry.usd
parsing multibody/parsing/test/usd_parser_test/invalid/unsupported_geometry.usd
UsdParser is not available because WITH_USD is not ON
rico@PUGET-255560:~/checkout/drake3$ ./bazel-bin/multibody/parsing/parser_manual_test multibody/parsing/test/usd_parser_test/invalid/unsupported_geometry.unknown
parsing multibody/parsing/test/usd_parser_test/invalid/unsupported_geometry.unknown
error: The file 'multibody/parsing/test/usd_parser_test/invalid/unsupported_geometry.unknown' is not a recognized type. Known types are: .urdf, .sdf, .xml (Mujoco), .dmd.yaml, .obj

When WITH_USD=ON, we can start pondering the quality of our parser output (and whether we have control of it?):

rico@PUGET-255560:~/checkout/drake3$ ./bazel-bin/multibody/parsing/parser_manual_test multibody/parsing/test/usd_parser_test/invalid/unsupported_geometry.usda 
parsing multibody/parsing/test/usd_parser_test/invalid/unsupported_geometry.usda
Processing /World
Warning: in _GetGeneratedSchema at line 783 of external/openusd_internal/pxr/usd/usd/schemaRegistry.cpp -- Failed to open schema layer at path '/home/rico/.cache/bazel/_bazel_rico/15ff2e144c7e926083749497375aafc7/execroot/drake/bazel-out/k8-opt/bin/multibody/parsing/parser_manual_test.runfiles/openusd_internal/pxr/usd/usd/@PLUG_INFO_ROOT@/@PLUG_INFO_RESOURCE_PATH@/generatedSchema.usda'. Any schemas defined in plugin library 'usd' will not have valid prim definitions.
Warning (secondary thread): in _GetGeneratedSchema at line 783 of external/openusd_internal/pxr/usd/usd/schemaRegistry.cpp -- Failed to open schema layer at path '/home/rico/.cache/bazel/_bazel_rico/15ff2e144c7e926083749497375aafc7/execroot/drake/bazel-out/k8-opt/bin/multibody/parsing/parser_manual_test.runfiles/openusd_internal/pxr/usd/usdGeom/@PLUG_INFO_ROOT@/@PLUG_INFO_RESOURCE_PATH@/generatedSchema.usda'. Any schemas defined in plugin library 'usdGeom' will not have valid prim definitions.
Warning (secondary thread): in _GetGeneratedSchema at line 783 of external/openusd_internal/pxr/usd/usd/schemaRegistry.cpp -- Failed to open schema layer at path '/home/rico/.cache/bazel/_bazel_rico/15ff2e144c7e926083749497375aafc7/execroot/drake/bazel-out/k8-opt/bin/multibody/parsing/parser_manual_test.runfiles/openusd_internal/pxr/usd/usdShade/@PLUG_INFO_ROOT@/@PLUG_INFO_RESOURCE_PATH@/generatedSchema.usda'. Any schemas defined in plugin library 'usdShade' will not have valid prim definitions.
Warning (secondary thread): in _GetGeneratedSchema at line 783 of external/openusd_internal/pxr/usd/usd/schemaRegistry.cpp -- Failed to open schema layer at path '/home/rico/.cache/bazel/_bazel_rico/15ff2e144c7e926083749497375aafc7/execroot/drake/bazel-out/k8-opt/bin/multibody/parsing/parser_manual_test.runfiles/openusd_internal/pxr/usd/usdPhysics/@PLUG_INFO_ROOT@/@PLUG_INFO_RESOURCE_PATH@/generatedSchema.usda'. Any schemas defined in plugin library 'usdPhysics' will not have valid prim definitions.
Warning: in _MapSchematicsPropertyPaths at line 198 of external/openusd_internal/pxr/usd/usd/primDefinition.cpp -- No prim spec exists at path '/PhysicsRigidBodyAPI' in schematics layer anon:0x7510d40022c0:/home/rico/.cache/bazel/_bazel_rico/15ff2e144c7e926083749497375aafc7/execroot/drake/bazel-out/k8-opt/bin/multibody/parsing/parser_manual_test.runfiles/openusd_internal/pxr/usd/usdPhysics/@PLUG_INFO_ROOT@/@PLUG_INFO_RESOURCE_PATH@/generatedSchema.usda.
Warning: in _MapSchematicsPropertyPaths at line 198 of external/openusd_internal/pxr/usd/usd/primDefinition.cpp -- No prim spec exists at path '/MotionAPI' in schematics layer anon:0x7510e8001b90:/home/rico/.cache/bazel/_bazel_rico/15ff2e144c7e926083749497375aafc7/execroot/drake/bazel-out/k8-opt/bin/multibody/parsing/parser_manual_test.runfiles/openusd_internal/pxr/usd/usdGeom/@PLUG_INFO_ROOT@/@PLUG_INFO_RESOURCE_PATH@/generatedSchema.usda.
Warning: in _MapSchematicsPropertyPaths at line 198 of external/openusd_internal/pxr/usd/usd/primDefinition.cpp -- No prim spec exists at path '/CoordSysAPI' in schematics layer anon:0x751008001520:/home/rico/.cache/bazel/_bazel_rico/15ff2e144c7e926083749497375aafc7/execroot/drake/bazel-out/k8-opt/bin/multibody/parsing/parser_manual_test.runfiles/openusd_internal/pxr/usd/usdShade/@PLUG_INFO_ROOT@/@PLUG_INFO_RESOURCE_PATH@/generatedSchema.usda.
Warning: in _MapSchematicsPropertyPaths at line 198 of external/openusd_internal/pxr/usd/usd/primDefinition.cpp -- No prim spec exists at path '/PhysicsMeshCollisionAPI' in schematics layer anon:0x7510d40022c0:/home/rico/.cache/bazel/_bazel_rico/15ff2e144c7e926083749497375aafc7/execroot/drake/bazel-out/k8-opt/bin/multibody/parsing/parser_manual_test.runfiles/openusd_internal/pxr/usd/usdPhysics/@PLUG_INFO_ROOT@/@PLUG_INFO_RESOURCE_PATH@/generatedSchema.usda.
Warning: in _MapSchematicsPropertyPaths at line 198 of external/openusd_internal/pxr/usd/usd/primDefinition.cpp -- No prim spec exists at path '/PhysicsFilteredPairsAPI' in schematics layer anon:0x7510d40022c0:/home/rico/.cache/bazel/_bazel_rico/15ff2e144c7e926083749497375aafc7/execroot/drake/bazel-out/k8-opt/bin/multibody/parsing/parser_manual_test.runfiles/openusd_internal/pxr/usd/usdPhysics/@PLUG_INFO_ROOT@/@PLUG_INFO_RESOURCE_PATH@/generatedSchema.usda.
Warning: in _MapSchematicsPropertyPaths at line 198 of external/openusd_internal/pxr/usd/usd/primDefinition.cpp -- No prim spec exists at path '/PhysicsMassAPI' in schematics layer anon:0x7510d40022c0:/home/rico/.cache/bazel/_bazel_rico/15ff2e144c7e926083749497375aafc7/execroot/drake/bazel-out/k8-opt/bin/multibody/parsing/parser_manual_test.runfiles/openusd_internal/pxr/usd/usdPhysics/@PLUG_INFO_ROOT@/@PLUG_INFO_RESOURCE_PATH@/generatedSchema.usda.
Warning: in _MapSchematicsPropertyPaths at line 198 of external/openusd_internal/pxr/usd/usd/primDefinition.cpp -- No prim spec exists at path '/PhysicsCollisionAPI' in schematics layer anon:0x7510d40022c0:/home/rico/.cache/bazel/_bazel_rico/15ff2e144c7e926083749497375aafc7/execroot/drake/bazel-out/k8-opt/bin/multibody/parsing/parser_manual_test.runfiles/openusd_internal/pxr/usd/usdPhysics/@PLUG_INFO_ROOT@/@PLUG_INFO_RESOURCE_PATH@/generatedSchema.usda.
Warning: in _MapSchematicsPropertyPaths at line 198 of external/openusd_internal/pxr/usd/usd/primDefinition.cpp -- No prim spec exists at path '/PhysicsLimitAPI' in schematics layer anon:0x7510d40022c0:/home/rico/.cache/bazel/_bazel_rico/15ff2e144c7e926083749497375aafc7/execroot/drake/bazel-out/k8-opt/bin/multibody/parsing/parser_manual_test.runfiles/openusd_internal/pxr/usd/usdPhysics/@PLUG_INFO_ROOT@/@PLUG_INFO_RESOURCE_PATH@/generatedSchema.usda.
Warning: in _MapSchematicsPropertyPaths at line 198 of external/openusd_internal/pxr/usd/usd/primDefinition.cpp -- No prim spec exists at path '/PhysicsMaterialAPI' in schematics layer anon:0x7510d40022c0:/home/rico/.cache/bazel/_bazel_rico/15ff2e144c7e926083749497375aafc7/execroot/drake/bazel-out/k8-opt/bin/multibody/parsing/parser_manual_test.runfiles/openusd_internal/pxr/usd/usdPhysics/@PLUG_INFO_ROOT@/@PLUG_INFO_RESOURCE_PATH@/generatedSchema.usda.
Warning: in _MapSchematicsPropertyPaths at line 198 of external/openusd_internal/pxr/usd/usd/primDefinition.cpp -- No prim spec exists at path '/VisibilityAPI' in schematics layer anon:0x7510e8001b90:/home/rico/.cache/bazel/_bazel_rico/15ff2e144c7e926083749497375aafc7/execroot/drake/bazel-out/k8-opt/bin/multibody/parsing/parser_manual_test.runfiles/openusd_internal/pxr/usd/usdGeom/@PLUG_INFO_ROOT@/@PLUG_INFO_RESOURCE_PATH@/generatedSchema.usda.
Warning: in _MapSchematicsPropertyPaths at line 198 of external/openusd_internal/pxr/usd/usd/primDefinition.cpp -- No prim spec exists at path '/CollectionAPI' in schematics layer anon:0x654f28c21a80:/home/rico/.cache/bazel/_bazel_rico/15ff2e144c7e926083749497375aafc7/execroot/drake/bazel-out/k8-opt/bin/multibody/parsing/parser_manual_test.runfiles/openusd_internal/pxr/usd/usd/@PLUG_INFO_ROOT@/@PLUG_INFO_RESOURCE_PATH@/generatedSchema.usda.
Warning: in _MapSchematicsPropertyPaths at line 198 of external/openusd_internal/pxr/usd/usd/primDefinition.cpp -- No prim spec exists at path '/PhysicsArticulationRootAPI' in schematics layer anon:0x7510d40022c0:/home/rico/.cache/bazel/_bazel_rico/15ff2e144c7e926083749497375aafc7/execroot/drake/bazel-out/k8-opt/bin/multibody/parsing/parser_manual_test.runfiles/openusd_internal/pxr/usd/usdPhysics/@PLUG_INFO_ROOT@/@PLUG_INFO_RESOURCE_PATH@/generatedSchema.usda.
Warning: in _MapSchematicsPropertyPaths at line 198 of external/openusd_internal/pxr/usd/usd/primDefinition.cpp -- No prim spec exists at path '/NodeDefAPI' in schematics layer anon:0x751008001520:/home/rico/.cache/bazel/_bazel_rico/15ff2e144c7e926083749497375aafc7/execroot/drake/bazel-out/k8-opt/bin/multibody/parsing/parser_manual_test.runfiles/openusd_internal/pxr/usd/usdShade/@PLUG_INFO_ROOT@/@PLUG_INFO_RESOURCE_PATH@/generatedSchema.usda.
Warning: in _MapSchematicsPropertyPaths at line 198 of external/openusd_internal/pxr/usd/usd/primDefinition.cpp -- No prim spec exists at path '/PhysicsDriveAPI' in schematics layer anon:0x7510d40022c0:/home/rico/.cache/bazel/_bazel_rico/15ff2e144c7e926083749497375aafc7/execroot/drake/bazel-out/k8-opt/bin/multibody/parsing/parser_manual_test.runfiles/openusd_internal/pxr/usd/usdPhysics/@PLUG_INFO_ROOT@/@PLUG_INFO_RESOURCE_PATH@/generatedSchema.usda.
Warning: in _MapSchematicsPropertyPaths at line 198 of external/openusd_internal/pxr/usd/usd/primDefinition.cpp -- No prim spec exists at path '/MaterialBindingAPI' in schematics layer anon:0x751008001520:/home/rico/.cache/bazel/_bazel_rico/15ff2e144c7e926083749497375aafc7/execroot/drake/bazel-out/k8-opt/bin/multibody/parsing/parser_manual_test.runfiles/openusd_internal/pxr/usd/usdShade/@PLUG_INFO_ROOT@/@PLUG_INFO_RESOURCE_PATH@/generatedSchema.usda.
Warning: in _MapSchematicsPropertyPaths at line 198 of external/openusd_internal/pxr/usd/usd/primDefinition.cpp -- No prim spec exists at path '/GeomModelAPI' in schematics layer anon:0x7510e8001b90:/home/rico/.cache/bazel/_bazel_rico/15ff2e144c7e926083749497375aafc7/execroot/drake/bazel-out/k8-opt/bin/multibody/parsing/parser_manual_test.runfiles/openusd_internal/pxr/usd/usdGeom/@PLUG_INFO_ROOT@/@PLUG_INFO_RESOURCE_PATH@/generatedSchema.usda.
Warning: in _MapSchematicsPropertyPaths at line 198 of external/openusd_internal/pxr/usd/usd/primDefinition.cpp -- No prim spec exists at path '/Shader' in schematics layer anon:0x751008001520:/home/rico/.cache/bazel/_bazel_rico/15ff2e144c7e926083749497375aafc7/execroot/drake/bazel-out/k8-opt/bin/multibody/parsing/parser_manual_test.runfiles/openusd_internal/pxr/usd/usdShade/@PLUG_INFO_ROOT@/@PLUG_INFO_RESOURCE_PATH@/generatedSchema.usda.
Warning: in _MapSchematicsPropertyPaths at line 198 of external/openusd_internal/pxr/usd/usd/primDefinition.cpp -- No prim spec exists at path '/Material' in schematics layer anon:0x751008001520:/home/rico/.cache/bazel/_bazel_rico/15ff2e144c7e926083749497375aafc7/execroot/drake/bazel-out/k8-opt/bin/multibody/parsing/parser_manual_test.runfiles/openusd_internal/pxr/usd/usdShade/@PLUG_INFO_ROOT@/@PLUG_INFO_RESOURCE_PATH@/generatedSchema.usda.
Warning: in _MapSchematicsPropertyPaths at line 198 of external/openusd_internal/pxr/usd/usd/primDefinition.cpp -- No prim spec exists at path '/Capsule' in schematics layer anon:0x7510e8001b90:/home/rico/.cache/bazel/_bazel_rico/15ff2e144c7e926083749497375aafc7/execroot/drake/bazel-out/k8-opt/bin/multibody/parsing/parser_manual_test.runfiles/openusd_internal/pxr/usd/usdGeom/@PLUG_INFO_ROOT@/@PLUG_INFO_RESOURCE_PATH@/generatedSchema.usda.
Warning: in _MapSchematicsPropertyPaths at line 198 of external/openusd_internal/pxr/usd/usd/primDefinition.cpp -- No prim spec exists at path '/Mesh' in schematics layer anon:0x7510e8001b90:/home/rico/.cache/bazel/_bazel_rico/15ff2e144c7e926083749497375aafc7/execroot/drake/bazel-out/k8-opt/bin/multibody/parsing/parser_manual_test.runfiles/openusd_internal/pxr/usd/usdGeom/@PLUG_INFO_ROOT@/@PLUG_INFO_RESOURCE_PATH@/generatedSchema.usda.
Warning: in _MapSchematicsPropertyPaths at line 198 of external/openusd_internal/pxr/usd/usd/primDefinition.cpp -- No prim spec exists at path '/PhysicsScene' in schematics layer anon:0x7510d40022c0:/home/rico/.cache/bazel/_bazel_rico/15ff2e144c7e926083749497375aafc7/execroot/drake/bazel-out/k8-opt/bin/multibody/parsing/parser_manual_test.runfiles/openusd_internal/pxr/usd/usdPhysics/@PLUG_INFO_ROOT@/@PLUG_INFO_RESOURCE_PATH@/generatedSchema.usda.
Warning: in _MapSchematicsPropertyPaths at line 198 of external/openusd_internal/pxr/usd/usd/primDefinition.cpp -- No prim spec exists at path '/PhysicsRevoluteJoint' in schematics layer anon:0x7510d40022c0:/home/rico/.cache/bazel/_bazel_rico/15ff2e144c7e926083749497375aafc7/execroot/drake/bazel-out/k8-opt/bin/multibody/parsing/parser_manual_test.runfiles/openusd_internal/pxr/usd/usdPhysics/@PLUG_INFO_ROOT@/@PLUG_INFO_RESOURCE_PATH@/generatedSchema.usda.
Warning: in _MapSchematicsPropertyPaths at line 198 of external/openusd_internal/pxr/usd/usd/primDefinition.cpp -- No prim spec exists at path '/PhysicsJoint' in schematics layer anon:0x7510d40022c0:/home/rico/.cache/bazel/_bazel_rico/15ff2e144c7e926083749497375aafc7/execroot/drake/bazel-out/k8-opt/bin/multibody/parsing/parser_manual_test.runfiles/openusd_internal/pxr/usd/usdPhysics/@PLUG_INFO_ROOT@/@PLUG_INFO_RESOURCE_PATH@/generatedSchema.usda.
Warning: in _MapSchematicsPropertyPaths at line 198 of external/openusd_internal/pxr/usd/usd/primDefinition.cpp -- No prim spec exists at path '/PhysicsPrismaticJoint' in schematics layer anon:0x7510d40022c0:/home/rico/.cache/bazel/_bazel_rico/15ff2e144c7e926083749497375aafc7/execroot/drake/bazel-out/k8-opt/bin/multibody/parsing/parser_manual_test.runfiles/openusd_internal/pxr/usd/usdPhysics/@PLUG_INFO_ROOT@/@PLUG_INFO_RESOURCE_PATH@/generatedSchema.usda.
Warning: in _MapSchematicsPropertyPaths at line 198 of external/openusd_internal/pxr/usd/usd/primDefinition.cpp -- No prim spec exists at path '/NurbsCurves' in schematics layer anon:0x7510e8001b90:/home/rico/.cache/bazel/_bazel_rico/15ff2e144c7e926083749497375aafc7/execroot/drake/bazel-out/k8-opt/bin/multibody/parsing/parser_manual_test.runfiles/openusd_internal/pxr/usd/usdGeom/@PLUG_INFO_ROOT@/@PLUG_INFO_RESOURCE_PATH@/generatedSchema.usda.
Warning: in _MapSchematicsPropertyPaths at line 198 of external/openusd_internal/pxr/usd/usd/primDefinition.cpp -- No prim spec exists at path '/Xform' in schematics layer anon:0x7510e8001b90:/home/rico/.cache/bazel/_bazel_rico/15ff2e144c7e926083749497375aafc7/execroot/drake/bazel-out/k8-opt/bin/multibody/parsing/parser_manual_test.runfiles/openusd_internal/pxr/usd/usdGeom/@PLUG_INFO_ROOT@/@PLUG_INFO_RESOURCE_PATH@/generatedSchema.usda.
Warning: in _MapSchematicsPropertyPaths at line 198 of external/openusd_internal/pxr/usd/usd/primDefinition.cpp -- No prim spec exists at path '/NodeGraph' in schematics layer anon:0x751008001520:/home/rico/.cache/bazel/_bazel_rico/15ff2e144c7e926083749497375aafc7/execroot/drake/bazel-out/k8-opt/bin/multibody/parsing/parser_manual_test.runfiles/openusd_internal/pxr/usd/usdShade/@PLUG_INFO_ROOT@/@PLUG_INFO_RESOURCE_PATH@/generatedSchema.usda.
Warning: in _MapSchematicsPropertyPaths at line 198 of external/openusd_internal/pxr/usd/usd/primDefinition.cpp -- No prim spec exists at path '/Capsule_1' in schematics layer anon:0x7510e8001b90:/home/rico/.cache/bazel/_bazel_rico/15ff2e144c7e926083749497375aafc7/execroot/drake/bazel-out/k8-opt/bin/multibody/parsing/parser_manual_test.runfiles/openusd_internal/pxr/usd/usdGeom/@PLUG_INFO_ROOT@/@PLUG_INFO_RESOURCE_PATH@/generatedSchema.usda.
Warning: in _MapSchematicsPropertyPaths at line 198 of external/openusd_internal/pxr/usd/usd/primDefinition.cpp -- No prim spec exists at path '/Cylinder_1' in schematics layer anon:0x7510e8001b90:/home/rico/.cache/bazel/_bazel_rico/15ff2e144c7e926083749497375aafc7/execroot/drake/bazel-out/k8-opt/bin/multibody/parsing/parser_manual_test.runfiles/openusd_internal/pxr/usd/usdGeom/@PLUG_INFO_ROOT@/@PLUG_INFO_RESOURCE_PATH@/generatedSchema.usda.
Warning: in _MapSchematicsPropertyPaths at line 198 of external/openusd_internal/pxr/usd/usd/primDefinition.cpp -- No prim spec exists at path '/Cylinder' in schematics layer anon:0x7510e8001b90:/home/rico/.cache/bazel/_bazel_rico/15ff2e144c7e926083749497375aafc7/execroot/drake/bazel-out/k8-opt/bin/multibody/parsing/parser_manual_test.runfiles/openusd_internal/pxr/usd/usdGeom/@PLUG_INFO_ROOT@/@PLUG_INFO_RESOURCE_PATH@/generatedSchema.usda.
Warning: in _MapSchematicsPropertyPaths at line 198 of external/openusd_internal/pxr/usd/usd/primDefinition.cpp -- No prim spec exists at path '/PhysicsCollisionGroup' in schematics layer anon:0x7510d40022c0:/home/rico/.cache/bazel/_bazel_rico/15ff2e144c7e926083749497375aafc7/execroot/drake/bazel-out/k8-opt/bin/multibody/parsing/parser_manual_test.runfiles/openusd_internal/pxr/usd/usdPhysics/@PLUG_INFO_ROOT@/@PLUG_INFO_RESOURCE_PATH@/generatedSchema.usda.
Warning: in _MapSchematicsPropertyPaths at line 198 of external/openusd_internal/pxr/usd/usd/primDefinition.cpp -- No prim spec exists at path '/PhysicsFixedJoint' in schematics layer anon:0x7510d40022c0:/home/rico/.cache/bazel/_bazel_rico/15ff2e144c7e926083749497375aafc7/execroot/drake/bazel-out/k8-opt/bin/multibody/parsing/parser_manual_test.runfiles/openusd_internal/pxr/usd/usdPhysics/@PLUG_INFO_ROOT@/@PLUG_INFO_RESOURCE_PATH@/generatedSchema.usda.
Warning: in _MapSchematicsPropertyPaths at line 198 of external/openusd_internal/pxr/usd/usd/primDefinition.cpp -- No prim spec exists at path '/Plane' in schematics layer anon:0x7510e8001b90:/home/rico/.cache/bazel/_bazel_rico/15ff2e144c7e926083749497375aafc7/execroot/drake/bazel-out/k8-opt/bin/multibody/parsing/parser_manual_test.runfiles/openusd_internal/pxr/usd/usdGeom/@PLUG_INFO_ROOT@/@PLUG_INFO_RESOURCE_PATH@/generatedSchema.usda.
Warning: in _MapSchematicsPropertyPaths at line 198 of external/openusd_internal/pxr/usd/usd/primDefinition.cpp -- No prim spec exists at path '/PhysicsDistanceJoint' in schematics layer anon:0x7510d40022c0:/home/rico/.cache/bazel/_bazel_rico/15ff2e144c7e926083749497375aafc7/execroot/drake/bazel-out/k8-opt/bin/multibody/parsing/parser_manual_test.runfiles/openusd_internal/pxr/usd/usdPhysics/@PLUG_INFO_ROOT@/@PLUG_INFO_RESOURCE_PATH@/generatedSchema.usda.
Warning: in _MapSchematicsPropertyPaths at line 198 of external/openusd_internal/pxr/usd/usd/primDefinition.cpp -- No prim spec exists at path '/NurbsPatch' in schematics layer anon:0x7510e8001b90:/home/rico/.cache/bazel/_bazel_rico/15ff2e144c7e926083749497375aafc7/execroot/drake/bazel-out/k8-opt/bin/multibody/parsing/parser_manual_test.runfiles/openusd_internal/pxr/usd/usdGeom/@PLUG_INFO_ROOT@/@PLUG_INFO_RESOURCE_PATH@/generatedSchema.usda.
Warning: in _MapSchematicsPropertyPaths at line 198 of external/openusd_internal/pxr/usd/usd/primDefinition.cpp -- No prim spec exists at path '/BasisCurves' in schematics layer anon:0x7510e8001b90:/home/rico/.cache/bazel/_bazel_rico/15ff2e144c7e926083749497375aafc7/execroot/drake/bazel-out/k8-opt/bin/multibody/parsing/parser_manual_test.runfiles/openusd_internal/pxr/usd/usdGeom/@PLUG_INFO_ROOT@/@PLUG_INFO_RESOURCE_PATH@/generatedSchema.usda.
Warning: in _MapSchematicsPropertyPaths at line 198 of external/openusd_internal/pxr/usd/usd/primDefinition.cpp -- No prim spec exists at path '/PointInstancer' in schematics layer anon:0x7510e8001b90:/home/rico/.cache/bazel/_bazel_rico/15ff2e144c7e926083749497375aafc7/execroot/drake/bazel-out/k8-opt/bin/multibody/parsing/parser_manual_test.runfiles/openusd_internal/pxr/usd/usdGeom/@PLUG_INFO_ROOT@/@PLUG_INFO_RESOURCE_PATH@/generatedSchema.usda.
Warning: in _MapSchematicsPropertyPaths at line 198 of external/openusd_internal/pxr/usd/usd/primDefinition.cpp -- No prim spec exists at path '/Camera' in schematics layer anon:0x7510e8001b90:/home/rico/.cache/bazel/_bazel_rico/15ff2e144c7e926083749497375aafc7/execroot/drake/bazel-out/k8-opt/bin/multibody/parsing/parser_manual_test.runfiles/openusd_internal/pxr/usd/usdGeom/@PLUG_INFO_ROOT@/@PLUG_INFO_RESOURCE_PATH@/generatedSchema.usda.
Warning: in _MapSchematicsPropertyPaths at line 198 of external/openusd_internal/pxr/usd/usd/primDefinition.cpp -- No prim spec exists at path '/Cone' in schematics layer anon:0x7510e8001b90:/home/rico/.cache/bazel/_bazel_rico/15ff2e144c7e926083749497375aafc7/execroot/drake/bazel-out/k8-opt/bin/multibody/parsing/parser_manual_test.runfiles/openusd_internal/pxr/usd/usdGeom/@PLUG_INFO_ROOT@/@PLUG_INFO_RESOURCE_PATH@/generatedSchema.usda.
Warning: in _MapSchematicsPropertyPaths at line 198 of external/openusd_internal/pxr/usd/usd/primDefinition.cpp -- No prim spec exists at path '/Cube' in schematics layer anon:0x7510e8001b90:/home/rico/.cache/bazel/_bazel_rico/15ff2e144c7e926083749497375aafc7/execroot/drake/bazel-out/k8-opt/bin/multibody/parsing/parser_manual_test.runfiles/openusd_internal/pxr/usd/usdGeom/@PLUG_INFO_ROOT@/@PLUG_INFO_RESOURCE_PATH@/generatedSchema.usda.
Warning: in _MapSchematicsPropertyPaths at line 198 of external/openusd_internal/pxr/usd/usd/primDefinition.cpp -- No prim spec exists at path '/Sphere' in schematics layer anon:0x7510e8001b90:/home/rico/.cache/bazel/_bazel_rico/15ff2e144c7e926083749497375aafc7/execroot/drake/bazel-out/k8-opt/bin/multibody/parsing/parser_manual_test.runfiles/openusd_internal/pxr/usd/usdGeom/@PLUG_INFO_ROOT@/@PLUG_INFO_RESOURCE_PATH@/generatedSchema.usda.
Warning: in _MapSchematicsPropertyPaths at line 198 of external/openusd_internal/pxr/usd/usd/primDefinition.cpp -- No prim spec exists at path '/HermiteCurves' in schematics layer anon:0x7510e8001b90:/home/rico/.cache/bazel/_bazel_rico/15ff2e144c7e926083749497375aafc7/execroot/drake/bazel-out/k8-opt/bin/multibody/parsing/parser_manual_test.runfiles/openusd_internal/pxr/usd/usdGeom/@PLUG_INFO_ROOT@/@PLUG_INFO_RESOURCE_PATH@/generatedSchema.usda.
Warning: in _MapSchematicsPropertyPaths at line 198 of external/openusd_internal/pxr/usd/usd/primDefinition.cpp -- No prim spec exists at path '/Points' in schematics layer anon:0x7510e8001b90:/home/rico/.cache/bazel/_bazel_rico/15ff2e144c7e926083749497375aafc7/execroot/drake/bazel-out/k8-opt/bin/multibody/parsing/parser_manual_test.runfiles/openusd_internal/pxr/usd/usdGeom/@PLUG_INFO_ROOT@/@PLUG_INFO_RESOURCE_PATH@/generatedSchema.usda.
Warning: in _MapSchematicsPropertyPaths at line 198 of external/openusd_internal/pxr/usd/usd/primDefinition.cpp -- No prim spec exists at path '/Scope' in schematics layer anon:0x7510e8001b90:/home/rico/.cache/bazel/_bazel_rico/15ff2e144c7e926083749497375aafc7/execroot/drake/bazel-out/k8-opt/bin/multibody/parsing/parser_manual_test.runfiles/openusd_internal/pxr/usd/usdGeom/@PLUG_INFO_ROOT@/@PLUG_INFO_RESOURCE_PATH@/generatedSchema.usda.
Warning: in _MapSchematicsPropertyPaths at line 198 of external/openusd_internal/pxr/usd/usd/primDefinition.cpp -- No prim spec exists at path '/GeomSubset' in schematics layer anon:0x7510e8001b90:/home/rico/.cache/bazel/_bazel_rico/15ff2e144c7e926083749497375aafc7/execroot/drake/bazel-out/k8-opt/bin/multibody/parsing/parser_manual_test.runfiles/openusd_internal/pxr/usd/usdGeom/@PLUG_INFO_ROOT@/@PLUG_INFO_RESOURCE_PATH@/generatedSchema.usda.
Warning: in _MapSchematicsPropertyPaths at line 198 of external/openusd_internal/pxr/usd/usd/primDefinition.cpp -- No prim spec exists at path '/TetMesh' in schematics layer anon:0x7510e8001b90:/home/rico/.cache/bazel/_bazel_rico/15ff2e144c7e926083749497375aafc7/execroot/drake/bazel-out/k8-opt/bin/multibody/parsing/parser_manual_test.runfiles/openusd_internal/pxr/usd/usdGeom/@PLUG_INFO_ROOT@/@PLUG_INFO_RESOURCE_PATH@/generatedSchema.usda.
Warning: in _MapSchematicsPropertyPaths at line 198 of external/openusd_internal/pxr/usd/usd/primDefinition.cpp -- No prim spec exists at path '/PhysicsSphericalJoint' in schematics layer anon:0x7510d40022c0:/home/rico/.cache/bazel/_bazel_rico/15ff2e144c7e926083749497375aafc7/execroot/drake/bazel-out/k8-opt/bin/multibody/parsing/parser_manual_test.runfiles/openusd_internal/pxr/usd/usdPhysics/@PLUG_INFO_ROOT@/@PLUG_INFO_RESOURCE_PATH@/generatedSchema.usda.
Processing /World/Box
error: Unsupported Prim type: 

We are clearly getting a lot of spam from inside OpenUSD -- eventually (maybe not this PR) we will want to get control of that. It also looks like the diagnostic we generate is not yet very useful. It might be to early to demand file names and line numbers, but it looks like we are not even printing context we think we have.

Thanks for the patch! Regarding the error message:

pxr::TfToken prim_type = prim.GetTypeName();
w_.diagnostic.Error(fmt::format("Unsupported Prim type: {}", prim_type));

In this particular case, the message error: Unsupported Prim type: isn't particular helpful because the type of the Prim in question is empty/unspecified, which evaluates to an empty string. This happened because the Prim was defined like this:

def "Box" (

whereas usually, there should be a type name specified before the name of the Prim, i.e.,

def Cube "Box" (

To improve this not-so-helpful message, I made the following change:

pxr::TfToken prim_type = prim.GetTypeName();
if (prim_type == "") {
  prim_type = pxr::TfToken("EmptyType");
}
w_.diagnostic.Error(fmt::format("Unsupported Prim type ({}) at {}", prim_type, prim.GetPath().GetString()));

which results in the following:

error: Unsupported Prim type 'EmptyType' at /World/Box

I don't think we're able to query the line number of a Prim within a USD file, so instead, the new message tells the user where exactly this unsupported Prim is at, which helps them debug.


Copy link
Contributor

@rpoyner-tri rpoyner-tri left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

BTW I did read the "rigid body physics proposal" on the OpenUSD doc site -- good stuff. It does have some discussion about defaults of various quantities; it's probably a good guide for default behavior for this parser.

Reviewed 1 of 3 files at r9, 2 of 2 files at r10.
Reviewable status: 4 unresolved discussions, LGTM missing from assignee rpoyner-tri(platform), needs at least two assigned reviewers, commits need curation (https://drake.mit.edu/reviewable.html#curated-commits) (waiting on @hong-nvidia)

a discussion (no related file):

Previously, hong-nvidia wrote…

Thanks for the patch! Regarding the error message:

pxr::TfToken prim_type = prim.GetTypeName();
w_.diagnostic.Error(fmt::format("Unsupported Prim type: {}", prim_type));

In this particular case, the message error: Unsupported Prim type: isn't particular helpful because the type of the Prim in question is empty/unspecified, which evaluates to an empty string. This happened because the Prim was defined like this:

def "Box" (

whereas usually, there should be a type name specified before the name of the Prim, i.e.,

def Cube "Box" (

To improve this not-so-helpful message, I made the following change:

pxr::TfToken prim_type = prim.GetTypeName();
if (prim_type == "") {
  prim_type = pxr::TfToken("EmptyType");
}
w_.diagnostic.Error(fmt::format("Unsupported Prim type ({}) at {}", prim_type, prim.GetPath().GetString()));

which results in the following:

error: Unsupported Prim type 'EmptyType' at /World/Box

I don't think we're able to query the line number of a Prim within a USD file, so instead, the new message tells the user where exactly this unsupported Prim is at, which helps them debug.

Got it. I do worry that absent the ability to provide file and line, users might be fooled into searching the input for the string "EmptyType". Maybe better to have custom wording for that case?


a discussion (no related file):
The build failures in the exported symbol test are coming from lex/yacc-style generated code inside OpenUSD. I may do a quick investigation, but welcome the wisdom of @jwnimmer-tri as well.



multibody/parsing/detail_usd_geometry.cc line 67 at r1 (raw file):

Previously, hong-nvidia wrote…

I see. In the case of USD, if an attribute doesn't exist or it doesn't contain a value, the read operation would just fail.

I think we can defend "mass = 1.0" by reference to the rigid body physics proposal, perhaps here, but certainly in the function doc comments.

Copy link
Collaborator

@jwnimmer-tri jwnimmer-tri left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Reviewable status: 4 unresolved discussions, LGTM missing from assignee rpoyner-tri(platform), needs at least two assigned reviewers, commits need curation (https://drake.mit.edu/reviewable.html#curated-commits) (waiting on @hong-nvidia)

a discussion (no related file):

Previously, rpoyner-tri (Rick Poyner (rico)) wrote…

The build failures in the exported symbol test are coming from lex/yacc-style generated code inside OpenUSD. I may do a quick investigation, but welcome the wisdom of @jwnimmer-tri as well.

Some of the bad symbols seem to come from textFileFormat.lex.cpp. On first glance, it seems like that file might not include any C++ headers (not even the C++ standard library). If that's true, then it would be safe to add copts = ["-fvisibility=hidden"] to the cc_library rule for that one file (not other files!). That should fix the test errors for symbols from that file. I didn't look if there was more than one bad file.

Or if injecting copts is too difficult, IIRC there's a way to do the same with a source code pragma, which you could inject via a *.patch file.


Copy link
Contributor

@rpoyner-tri rpoyner-tri left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Reviewable status: 4 unresolved discussions, LGTM missing from assignee rpoyner-tri(platform), needs at least two assigned reviewers, commits need curation (https://drake.mit.edu/reviewable.html#curated-commits) (waiting on @hong-nvidia)

a discussion (no related file):

Previously, jwnimmer-tri (Jeremy Nimmer) wrote…

Some of the bad symbols seem to come from textFileFormat.lex.cpp. On first glance, it seems like that file might not include any C++ headers (not even the C++ standard library). If that's true, then it would be safe to add copts = ["-fvisibility=hidden"] to the cc_library rule for that one file (not other files!). That should fix the test errors for symbols from that file. I didn't look if there was more than one bad file.

Or if injecting copts is too difficult, IIRC there's a way to do the same with a source code pragma, which you could inject via a *.patch file.

Sadly, there are some c++ headers deep down (line 2000 or later). A patch is still possible; I'll give it another try.


Copy link
Contributor

@rpoyner-tri rpoyner-tri left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Reviewable status: 4 unresolved discussions, LGTM missing from assignee rpoyner-tri(platform), needs at least two assigned reviewers, commits need curation (https://drake.mit.edu/reviewable.html#curated-commits) (waiting on @hong-nvidia)

a discussion (no related file):

Previously, rpoyner-tri (Rick Poyner (rico)) wrote…

Sadly, there are some c++ headers deep down (line 2000 or later). A patch is still possible; I'll give it another try.

In theory 🤞 , rebasing on a merged #21477 should make the exported_symbols_test failures go away.


Copy link
Author

@hong-nvidia hong-nvidia left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Reviewable status: 3 unresolved discussions, LGTM missing from assignee rpoyner-tri(platform), needs at least two assigned reviewers, commits need curation (https://drake.mit.edu/reviewable.html#curated-commits)

a discussion (no related file):

Previously, rpoyner-tri (Rick Poyner (rico)) wrote…

The symbol leak fix is merged now; if you rebase on newer master, many of the build failures should go away.

Got it. I've rebased to latest master.



multibody/parsing/detail_usd_geometry.h line 1 at r19 (raw file):

Previously, rpoyner-tri (Rick Poyner (rico)) wrote…

This file needs to have #pragma once as its first line. https://drake.mit.edu/styleguide/cppguide.html#The__pragma_once_Guard

Fixed.

Copy link
Contributor

@rpoyner-tri rpoyner-tri left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Reviewable status: 2 unresolved discussions, LGTM missing from assignee rpoyner-tri(platform), needs at least two assigned reviewers, commits need curation (https://drake.mit.edu/reviewable.html#curated-commits) (waiting on @hong-nvidia)

a discussion (no related file):

Previously, hong-nvidia wrote…

Got it. I've rebased to latest master.

Hm. Looks like there are some un-converted [blah]PXR_INTERNAL_NS[blah] symbols stilll leaking. I believe those were supposed to get preprocessed into something else, like roughly [blah]pxr_drake_vendor_[blah], which the symbol test would see in its allow lists.

I saw this briefly in testing the other patch, but then it mysteriously went away. I'll take another look.


Copy link
Contributor

@rpoyner-tri rpoyner-tri left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Reviewable status: 2 unresolved discussions, LGTM missing from assignee rpoyner-tri(platform), needs at least two assigned reviewers, commits need curation (https://drake.mit.edu/reviewable.html#curated-commits) (waiting on @hong-nvidia)

a discussion (no related file):

Previously, rpoyner-tri (Rick Poyner (rico)) wrote…

Hm. Looks like there are some un-converted [blah]PXR_INTERNAL_NS[blah] symbols stilll leaking. I believe those were supposed to get preprocessed into something else, like roughly [blah]pxr_drake_vendor_[blah], which the symbol test would see in its allow lists.

I saw this briefly in testing the other patch, but then it mysteriously went away. I'll take another look.

I've made some progress here, but there is apparently more to do. I've crafted a patch to take care of the problem described just above, but now I've to tbb::detail symbols leaking. I'll probably wait until I've hit the end of the line on these before I offer the fixes as drake PRs. Hopefully there's not too much more.


Copy link
Contributor

@rpoyner-tri rpoyner-tri left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Reviewable status: 2 unresolved discussions, LGTM missing from assignee rpoyner-tri(platform), needs at least two assigned reviewers, commits need curation (https://drake.mit.edu/reviewable.html#curated-commits) (waiting on @hong-nvidia)

a discussion (no related file):

Previously, rpoyner-tri (Rick Poyner (rico)) wrote…

I've made some progress here, but there is apparently more to do. I've crafted a patch to take care of the problem described just above, but now I've to tbb::detail symbols leaking. I'll probably wait until I've hit the end of the line on these before I offer the fixes as drake PRs. Hopefully there's not too much more.

See #21549 for another bit of symbol leak fixing. At least one more is still needed.


Copy link
Contributor

@rpoyner-tri rpoyner-tri left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Reviewable status: 2 unresolved discussions, LGTM missing from assignee rpoyner-tri(platform), needs at least two assigned reviewers, commits need curation (https://drake.mit.edu/reviewable.html#curated-commits) (waiting on @hong-nvidia)

a discussion (no related file):

Previously, rpoyner-tri (Rick Poyner (rico)) wrote…

See #21549 for another bit of symbol leak fixing. At least one more is still needed.

Still remaining categories of symbol leakage:

  • tbb::detail -- 192 symbols
  • PXR_WORK_THREAD_LIMIT -- 4 symbols, but all essentially the same thing?

* pegtl_namespace.patch

This patch allows the drake_vendor namespace modifications to be
reflected in TAO_PEGTL_NAMESPACE, which in turn allows the resulting
symbols to be matched by allow lists in exported_symbols_test.

* work_thread_limits_namespace.patch

This patch puts some macro-generated globals inside the library
namespace.

* Also, alpha-sort the patch file names.
Copy link
Contributor

@rpoyner-tri rpoyner-tri left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Reviewable status: 2 unresolved discussions, LGTM missing from assignee rpoyner-tri(platform), needs at least two assigned reviewers, commits need curation (https://drake.mit.edu/reviewable.html#curated-commits) (waiting on @hong-nvidia)

a discussion (no related file):

Previously, rpoyner-tri (Rick Poyner (rico)) wrote…

Still remaining categories of symbol leakage:

  • tbb::detail -- 192 symbols
  • PXR_WORK_THREAD_LIMIT -- 4 symbols, but all essentially the same thing?

Weirdly, patching PXR_WORK_THREAD_LIMIT seems to have caused the tbb::detail complaints to go away. I don't understand it.

Also, on advice of @jwnimmer-tri, I'm pushing symbol leak fixes directly to your branch to get timely CI feedback. You would need to update your local branch from your fork to see those changes.


Copy link
Contributor

@rpoyner-tri rpoyner-tri left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Reviewable status: 2 unresolved discussions, LGTM missing from assignee rpoyner-tri(platform), needs at least two assigned reviewers, commits need curation (https://drake.mit.edu/reviewable.html#curated-commits) (waiting on @hong-nvidia)

a discussion (no related file):

Previously, rpoyner-tri (Rick Poyner (rico)) wrote…

Weirdly, patching PXR_WORK_THREAD_LIMIT seems to have caused the tbb::detail complaints to go away. I don't understand it.

Also, on advice of @jwnimmer-tri, I'm pushing symbol leak fixes directly to your branch to get timely CI feedback. You would need to update your local branch from your fork to see those changes.

CI tells us that the tbb::detail leaks are still present. The tbb build used in drake is quite the sleigh-ride (binaries from mosek, magically matched headers, etc.). I'm appealing to @jwnimmer-tri for advice on how to dispose of the 192 remaining symbol leaks.


Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
release notes: feature This pull request contains a new feature
Projects
None yet
Development

Successfully merging this pull request may close these issues.

None yet

3 participants