Skip to content

Commit

Permalink
Model Directives mechanism for scene assembly.
Browse files Browse the repository at this point in the history
 * Toward RobotLocomotion#13282
 * A domain-specific language for assembling MultibodyPlant scenes
   from multiple SDF files.
 * Helpful for assembling large scenes without huge unwieldy sdf/xacro
   files.
 * A temporary accomodation until sdformat adds similar functionality.
  • Loading branch information
ggould-tri committed Aug 18, 2020
1 parent 50b90c3 commit 31eea59
Show file tree
Hide file tree
Showing 16 changed files with 259 additions and 85 deletions.
1 change: 1 addition & 0 deletions common/schema/dev/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -39,6 +39,7 @@ drake_cc_library(
name = "transform",
srcs = ["transform.cc"],
hdrs = ["transform.h"],
visibility = ["//multibody/parsing/dev:__pkg__"],
deps = [
":rotation",
":stochastic",
Expand Down
4 changes: 2 additions & 2 deletions common/schema/dev/rotation.h
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@ struct Rotation {
Identity() = default;

template <typename Archive>
void Serialize(Archive* a) {}
void Serialize(Archive*) {}
};

/// A roll-pitch-yaw rotation, using the angle conventions of Drake's
Expand Down Expand Up @@ -72,7 +72,7 @@ struct Rotation {
Uniform() = default;

template <typename Archive>
void Serialize(Archive* a) {}
void Serialize(Archive*) {}
};

/// Returns true iff this is fully deterministic.
Expand Down
64 changes: 64 additions & 0 deletions multibody/parsing/dev/BUILD.bazel
Original file line number Diff line number Diff line change
@@ -0,0 +1,64 @@
# -*- python -*-

load(
"@drake//tools/skylark:drake_cc.bzl",
"drake_cc_googletest",
"drake_cc_library",
)
load("//tools/lint:lint.bzl", "add_lint_tests")

drake_cc_library(
name = "process_model_directives",
srcs = ["process_model_directives.cc"],
hdrs = ["process_model_directives.h"],
data = [
"//manipulation/models/jaco_description:models",
],
deps = [
":model_directives",
"//common:filesystem",
"//common:find_resource",
"//common/yaml:yaml_read_archive",
"//multibody/parsing",
"//multibody/plant",
],
)

filegroup(
name = "process_model_directives_test_models",
testonly = True,
data = glob(["test/process_model_directives_test/**"]),
)

drake_cc_googletest(
name = "process_model_directives_test",
data = [
":process_model_directives_test_models",
],
deps = [
":process_model_directives",
],
)

drake_cc_library(
name = "model_directives",
hdrs = [
"model_directives.h",
],
deps = [
"//common:essential",
"//common:name_value",
"//common/schema/dev:transform",
"//math:geometric_transform",
],
)

drake_cc_googletest(
name = "model_directives_test",
deps = [
":model_directives",
"//common/yaml:yaml_read_archive",
],
)

add_lint_tests()
89 changes: 89 additions & 0 deletions multibody/parsing/dev/README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,89 @@
The Model Directives mechanism
==============================

Model Directives is a small yaml-based language for building a complex
MultibodyPlant-based scene out of numerous SDFs. For instance in the TRI
dish-loading demo we have individual SDF files for the counter, sink, cameras,
pedestal, arm, gripper, and each manipuland. A single SDF for this would be
unwieldy and difficult to maintain and collaborate on, but SDF's file
inclusion mechanisms have not yet proven adequate to this task.

We expect that this mechanism will be temporary and will be removed when
sdformat adds similar functionality. Users should be aware that this library
will be deprecated if/when sdformat reaches feature parity with it.


## Syntax

The easiest syntax reference is the unit test files in `test/models/*.yaml` of
this directory.

A model directives file is a yaml file with a top level `directives:` group.
Within this group are a series of directives:

* `AddModel` takes a `file` and `name` and loads the SDF/URDF file indicated
as a new model instance with the given name.
* `AddModelInstance` Creates a new, empty model instance in the plant with
the indicated `name`.
* `AddPackagePath` takes `name` and `path` and makes `package://name` URIs
be resolved to `path`. This directive is due for deprecation soon and
should generally be avoided.
* `AddFrame` takes a `name` and a `X_PF` transform and adds a new frame to
the model. Note that the transform is as specified in the `Transform`
scenario schema and can reference an optional base frame, in which case
the frame will be added to the base frame's model instance.
* `AddDirectives` takes a `file` naming a model directives file and an
optional `model_namespace`; it loads the model directives from that file
with the namespace prefixed to them (see Scoping, below).
* `AddWeld` takes a `parent` and `child` frame and welds them together.


## Use

The easiest use reference is the unit test `process_model_directives_test.cc`.

A simple example of a use would be:

```cpp
ModelDirectives station_directives = LoadModelDirectives(
FindResourceOrThrow("my_exciting_project/models/my_scene.yaml"));
MultibodyPlant<double> plant;
ProcessModelDirectives(station_directives, &plant);
plant.Finalize();
```
This loads the model directives from that filename, constructs a plant, and
uses the model directives to populate the plant.
## Scoping
Elements (frames, bodies, etc.) in `MultibodyPlant` belong to model instances.
Model instances can have any name specifiers, and can contain the "namespace"
delimiter `::`. Element names should not contain `::`.
Examples:
- `my_frame` implies no explicit model instance.
- `my_model::my_frame` implies the model instance `my_model`, the frame
`my_frame`.
- `top_level::my_model::my_frame` implies the model instance
`top_level::my_model`, the frame `my_frame`.
## Conditions for deprecation
We expect and hope to deprecate this mechanism when either:
SDF format properly specifies, and Drake supports, the following:
* What `<include/>` statements should *really* do (e.g. namespacing models,
joints, etc.) without kludging Drake's parsing
* How to weld models together with joints external to the models
OR if we find a mechanism whereby xacro could accomplish the same thing:
* Drake's `package://` / `model://` mechanism were mature and correct, and
`sdformat` didn't use singletons for search paths.
* It was easier for one xacro to locate other xacros (possibly via a
workaround using a wrapper script to inject `DRAKE_PATH`)
20 changes: 10 additions & 10 deletions multibody/parsing/dev/model_directives.h
Original file line number Diff line number Diff line change
Expand Up @@ -11,14 +11,14 @@

#include "drake/common/eigen_types.h"
#include "drake/common/name_value.h"
#include "drake/common/schema/dev/transform.h"
#include "drake/common/text_logging.h"
#include "drake/math/rigid_transform.h"
#include "drake/math/roll_pitch_yaw.h"
#include "common/schema/transform.h"

namespace anzu {
namespace common {
namespace schema {
namespace drake {
namespace multibody {
namespace parsing {

struct AddWeld {
bool IsValid() const {
Expand Down Expand Up @@ -128,7 +128,7 @@ struct AddFrame {
std::string name;
// Pose of frame to be added, `F`, w.r.t. parent frame `P` (as defined by
// `X_PF.base_frame`).
Transform X_PF;
drake::schema::Transform X_PF;
};

struct AddDirectives {
Expand Down Expand Up @@ -225,15 +225,15 @@ struct ModelDirectives {
inline void AddPackageToModelDirectives(const std::string& package_name,
const std::string& package_path,
ModelDirectives* directives) {
common::schema::AddPackagePath add_package_path;
AddPackagePath add_package_path;
add_package_path.name = package_name;
add_package_path.path = package_path;
common::schema::ModelDirective directive;
ModelDirective directive;
directive.add_package_path = add_package_path;
directives->directives.insert(
directives->directives.begin(), directive);
}

} // namespace schema
} // namespace common
} // namespace anzu
} // namespace parsing
} // namespace multibody
} // namespace drake
52 changes: 30 additions & 22 deletions multibody/parsing/dev/process_model_directives.cc
Original file line number Diff line number Diff line change
@@ -1,24 +1,24 @@
#include "common/process_model_directives.h"
#include "drake/multibody/parsing/dev/process_model_directives.h"

#include <memory>
#include <optional>
#include <string>
#include <utility>

#include "drake/common/filesystem.h"
#include "drake/common/find_resource.h"
#include "drake/common/schema/dev/transform.h"
#include "drake/common/yaml/yaml_read_archive.h"
#include "drake/multibody/parsing/parser.h"
#include "common/filesystem.h"
#include "common/find_resource.h"
#include "common/starts_with.h"
#include "common/yaml_load.h"

namespace anzu {
namespace common {
namespace drake {
namespace multibody {
namespace parsing {

using std::make_unique;
using Eigen::Isometry3d;

namespace fs = anzu::filesystem;
namespace fs = drake::filesystem;
using drake::FindResourceOrThrow;
using drake::math::RigidTransformd;
using drake::multibody::FixedOffsetFrame;
Expand All @@ -29,8 +29,6 @@ using drake::multibody::PackageMap;
using drake::multibody::Parser;
using drake::yaml::YamlReadArchive;

using schema::ModelDirectives;

namespace {

// If `*ptr` is null, construct `T(args...)` and reassign the pointer.
Expand All @@ -42,7 +40,7 @@ std::unique_ptr<T> ConstructIfNullAndReassign(T** ptr, Args&&... args) {
out = std::make_unique<T>(std::forward<Args>(args)...);
*ptr = out.get();
}
return std::move(out);
return out;
}

} // namespace
Expand Down Expand Up @@ -319,15 +317,23 @@ void ProcessModelDirectives(

ModelDirectives LoadModelDirectives(const std::string& filename) {
drake::log()->debug("LoadModelDirectives: {}", filename);
auto directives = common::YamlLoadWithDefaults<ModelDirectives>(filename);

// TODO(ggould-tri) This should use the YamlLoadWithDefaults mechanism
// instead once that is ported to drake.
ModelDirectives directives;
YAML::Node root = YAML::LoadFile(filename);
drake::yaml::YamlReadArchive::Options options;
options.allow_cpp_with_no_yaml = true;
drake::yaml::YamlReadArchive(root, options).Accept(&directives);

DRAKE_DEMAND(directives.IsValid());
return directives;
}

void FlattenModelDirectives(
const schema::ModelDirectives& directives,
const ModelDirectives& directives,
const PackageMap& package_map,
schema::ModelDirectives* out) {
ModelDirectives* out) {
// NOTE: Does not handle scoping!
for (auto& directive : directives.directives) {
if (directive.add_directives) {
Expand Down Expand Up @@ -356,9 +362,9 @@ ModelInfo MakeModelInfo(const std::string& model_name,

// TODO(eric.cousineau): Do we *really* need this function? This seems like
// it'd be better handled as an MBP subgraph.
schema::ModelDirectives MakeModelsAttachedToFrameDirectives(
ModelDirectives MakeModelsAttachedToFrameDirectives(
const std::vector<ModelInfo>& models_to_add) {
schema::ModelDirectives directives;
ModelDirectives directives;

// One for add frame, one for add model, one for add weld.
directives.directives.resize(models_to_add.size() * 3);
Expand All @@ -370,25 +376,26 @@ schema::ModelDirectives MakeModelsAttachedToFrameDirectives(

// Add frame first.
if (!model_to_add.X_PC.IsExactlyIdentity()) {
schema::AddFrame frame_dir;
AddFrame frame_dir;
attachment_frame_name = model_to_add.model_name + "_attachment_frame";
frame_dir.name = attachment_frame_name;
frame_dir.X_PF.base_frame = model_to_add.parent_frame_name;
frame_dir.X_PF.translation =
drake::Vector<double, 3>(model_to_add.X_PC.translation());
frame_dir.X_PF.rotation = schema::Rotation{model_to_add.X_PC.rotation()};
frame_dir.X_PF.rotation =
drake::schema::Rotation{model_to_add.X_PC.rotation()};

directives.directives.at(index++).add_frame = frame_dir;
}

// Add model
schema::AddModel model_dir;
AddModel model_dir;
model_dir.file = model_to_add.model_path;
model_dir.name = model_to_add.model_name;

directives.directives.at(index++).add_model = model_dir;

common::schema::AddWeld weld_dir;
AddWeld weld_dir;
weld_dir.parent = attachment_frame_name;
weld_dir.child =
model_to_add.model_name + "::" + model_to_add.child_frame_name;
Expand All @@ -399,5 +406,6 @@ schema::ModelDirectives MakeModelsAttachedToFrameDirectives(
return directives;
}

} // namespace common
} // namespace anzu
} // namespace parsing
} // namespace multibody
} // namespace drake
Loading

0 comments on commit 31eea59

Please sign in to comment.