Skip to content

Commit

Permalink
diagram builder: introduce AddNamedSystem sugar (RobotLocomotion#14404)
Browse files Browse the repository at this point in the history
* diagram builder: introduce AddNamedSystem sugar

Closes RobotLocomotion#5895.

This patch provides an potentially more fluent alternative to the common
AddSystem/set_name idiom.
  • Loading branch information
rpoyner-tri authored Dec 3, 2020
1 parent ac63939 commit aa4de29
Show file tree
Hide file tree
Showing 4 changed files with 159 additions and 60 deletions.
14 changes: 14 additions & 0 deletions bindings/pydrake/systems/framework_py_semantics.cc
Original file line number Diff line number Diff line change
Expand Up @@ -464,6 +464,20 @@ void DefineFrameworkPySemantics(py::module m) {
py::keep_alive<1, 0>(),
// Keep alive, ownership: `system` keeps `self` alive.
py::keep_alive<2, 1>(), doc.DiagramBuilder.AddSystem.doc)
.def(
"AddNamedSystem",
[](DiagramBuilder<T>* self, std::string& name,
unique_ptr<System<T>> system) {
return self->AddNamedSystem(name, std::move(system));
},
py::arg("name"), py::arg("system"),
// TODO(eric.cousineau): These two keep_alive's purposely form a
// reference cycle as a workaround for #14355. We should find a
// better way?
// Keep alive, reference: `self` keeps `return` alive.
py::keep_alive<1, 0>(),
// Keep alive, ownership: `system` keeps `self` alive.
py::keep_alive<3, 1>(), doc.DiagramBuilder.AddNamedSystem.doc)
.def("empty", &DiagramBuilder<T>::empty, doc.DiagramBuilder.empty.doc)
.def(
"GetSystems",
Expand Down
7 changes: 7 additions & 0 deletions bindings/pydrake/systems/test/general_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -891,3 +891,10 @@ def test_diagram_fan_out(self):
self.assertRegex(graph, "_u1 -> .*:u3")
self.assertRegex(graph, "_u0 -> .*:u4")
self.assertRegex(graph, "_u1 -> .*:u5")

def test_add_named_system(self):
builder = DiagramBuilder()
adder1 = builder.AddNamedSystem("adder1", Adder(2, 3))
self.assertEqual(adder1.get_name(), "adder1")
adder2 = builder.AddNamedSystem(name="adder2", system=Adder(5, 8))
self.assertEqual(adder2.get_name(), "adder2")
87 changes: 82 additions & 5 deletions systems/framework/diagram_builder.h
Original file line number Diff line number Diff line change
Expand Up @@ -21,8 +21,9 @@ namespace systems {
/// use: after calling Build or BuildInto, DiagramBuilder gives up ownership
/// of the constituent systems, and should therefore be discarded.
///
/// A system must be added to the DiagramBuilder with AddSystem before it can
/// be wired up in any way. Every system must have a unique, non-empty name.
/// A system must be added to the DiagramBuilder with AddSystem or
/// AddNamedSystem before it can be wired up in any way. Every system must have
/// a unique, non-empty name.
template <typename T>
class DiagramBuilder {
public:
Expand All @@ -32,9 +33,6 @@ class DiagramBuilder {
DiagramBuilder();
virtual ~DiagramBuilder();

// TODO(sherm1) The AddSystem methods (or some variant) should take the system
// name as their first parameter. See discussion in issue #5895.

/// Takes ownership of @p system and adds it to the builder. Returns a bare
/// pointer to the System, which will remain valid for the lifetime of the
/// Diagram built by this builder.
Expand Down Expand Up @@ -118,6 +116,85 @@ class DiagramBuilder {
return AddSystem(std::make_unique<S<T>>(std::forward<Args>(args)...));
}

/// Takes ownership of @p system, applies @p name to it, and adds it to the
/// builder. Returns a bare pointer to the System, which will remain valid
/// for the lifetime of the Diagram built by this builder.
///
/// @code
/// DiagramBuilder<T> builder;
/// auto bar = builder.AddNamedSystem("bar", std::make_unique<Bar<T>>());
/// @endcode
///
/// @tparam S The type of system to add.
/// @post The system's name is @p name.
template<class S>
S* AddNamedSystem(const std::string& name, std::unique_ptr<S> system) {
system->set_name(name);
return AddSystem(std::move(system));
}

/// Constructs a new system with the given @p args, applies @p name to it,
/// and adds it to the builder, which retains ownership. Returns a bare
/// pointer to the System, which will remain valid for the lifetime of the
/// Diagram built by this builder.
///
/// @code
/// DiagramBuilder<double> builder;
/// auto bar = builder.AddNamedSystem<Bar<double>>("bar", 3.14);
/// @endcode
///
/// Note that for dependent names you must use the template keyword:
///
/// @code
/// DiagramBuilder<T> builder;
/// auto bar = builder.template AddNamedSystem<Bar<T>>("bar", 3.14);
/// @endcode
///
/// You may prefer the `unique_ptr` variant instead.
///
/// @tparam S The type of System to construct. Must subclass System<T>.
/// @post The newly constructed system's name is @p name.
///
/// @exclude_from_pydrake_mkdoc{Not bound in pydrake -- emplacement while
/// specifying <T> doesn't make sense for that language.}
template<class S, typename... Args>
S* AddNamedSystem(const std::string& name, Args&&... args) {
return AddNamedSystem(
name, std::make_unique<S>(std::forward<Args>(args)...));
}

/// Constructs a new system with the given @p args, applies @p name to it,
/// and adds it to the builder, which retains ownership. Returns a bare
/// pointer to the System, which will remain valid for the lifetime of the
/// Diagram built by this builder.
///
/// @code
/// DiagramBuilder<double> builder;
/// // Bar must be a template.
/// auto bar = builder.AddNamedSystem<Bar>("bar", 3.14);
/// @endcode
///
/// Note that for dependent names you must use the template keyword:
///
/// @code
/// DiagramBuilder<T> builder;
/// auto bar = builder.template AddNamedSystem<Bar>("bar", 3.14);
/// @endcode
///
/// You may prefer the `unique_ptr` variant instead.
///
/// @tparam S A template for the type of System to construct. The template
/// will be specialized on the scalar type T of this builder.
/// @post The newly constructed system's name is @p name.
///
/// @exclude_from_pydrake_mkdoc{Not bound in pydrake -- emplacement while
/// specifying <T> doesn't make sense for that language.}
template<template<typename Scalar> class S, typename... Args>
S<T>* AddNamedSystem(const std::string& name, Args&&... args) {
return AddNamedSystem(
name, std::make_unique<S<T>>(std::forward<Args>(args)...));
}

/// Returns whether any Systems have been added yet.
bool empty() const { return registered_systems_.empty(); }

Expand Down
111 changes: 56 additions & 55 deletions systems/framework/test/diagram_builder_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,17 @@ GTEST_TEST(DiagramBuilderTest, Empty) {
EXPECT_FALSE(const_builder.empty());
}

// Tests ::AddNamedSystem() post-condition.
GTEST_TEST(DiagramBuilderTest, AddNamedSystem) {
DiagramBuilder<double> builder;
auto a = builder.AddNamedSystem("a", std::make_unique<Adder<double>>(2, 1));
EXPECT_EQ(a->get_name(), "a");
auto b = builder.AddNamedSystem<Adder<double>>("b", 2, 1);
EXPECT_EQ(b->get_name(), "b");
auto c = builder.AddNamedSystem<Adder>("c", 2 , 1);
EXPECT_EQ(c->get_name(), "c");
}

// A special class to distinguish between cycles and algebraic loops. The system
// has one input and two outputs. One output simply "echoes" the input (direct
// feedthrough). The other output merely outputs a const value. That means, the
Expand Down Expand Up @@ -76,10 +87,9 @@ class ConstAndEcho final : public LeafSystem<T> {
// Tests that an exception is thrown if the diagram contains an algebraic loop.
GTEST_TEST(DiagramBuilderTest, AlgebraicLoop) {
DiagramBuilder<double> builder;
auto adder = builder.AddSystem<Adder>(1 /* inputs */, 1 /* size */);
auto pass = builder.AddSystem<PassThrough>(1 /* size */);
adder->set_name("adder");
pass->set_name("pass");
auto adder = builder.AddNamedSystem<Adder>(
"adder", 1 /* inputs */, 1 /* size */);
auto pass = builder.AddNamedSystem<PassThrough>("pass", 1 /* size */);
// Connect the output port to the input port.
builder.Connect(adder->get_output_port(), pass->get_input_port());
builder.Connect(pass->get_output_port(), adder->get_input_port(0));
Expand Down Expand Up @@ -118,8 +128,7 @@ GTEST_TEST(DiagramBuilderTest, CycleButNoLoopPortLevel) {
// that is connected to input. So, the system has direct feedthrough, the
// diagram has a cycle at the *system* level, but there is no algebraic loop.

auto echo = builder.AddSystem<ConstAndEcho>();
echo->set_name("echo");
auto echo = builder.AddNamedSystem<ConstAndEcho>("echo");
builder.Connect(echo->get_const_output_port(), echo->get_vec_input_port());
DRAKE_EXPECT_NO_THROW(builder.Build());
}
Expand All @@ -144,9 +153,7 @@ GTEST_TEST(DiagramBuilderTest, CycleAtLoopPortLevel) {
// that is connected to input. So, the system has direct feeedthrough, the
// diagram has a cycle at the *system* level, but there is no algebraic loop.

auto echo = builder.AddSystem<ConstAndEcho>();
const std::string name{"echo"};
echo->set_name(name);
auto echo = builder.AddNamedSystem<ConstAndEcho>("echo");
builder.Connect(echo->get_echo_output_port(), echo->get_vec_input_port());
DRAKE_EXPECT_THROWS_MESSAGE(
builder.Build(), std::runtime_error,
Expand All @@ -171,10 +178,10 @@ GTEST_TEST(DiagramBuilderTest, CycleButNoAlgebraicLoopSystemLevel) {
// | Adder +---> Integrator -|
// |->| 1 | |---> output
// |------------------------------|
auto adder = builder.AddSystem<Adder>(2 /* inputs */, 1 /* size */);
adder->set_name("adder");
auto integrator = builder.AddSystem<Integrator>(1 /* size */);
integrator->set_name("integrator");
auto adder = builder.AddNamedSystem<Adder>(
"adder", 2 /* inputs */, 1 /* size */);
auto integrator = builder.AddNamedSystem<Integrator>(
"integrator", 1 /* size */);

builder.Connect(integrator->get_output_port(), adder->get_input_port(1));

Expand All @@ -187,10 +194,10 @@ GTEST_TEST(DiagramBuilderTest, CycleButNoAlgebraicLoopSystemLevel) {
GTEST_TEST(DiagramBuilderTest, CascadedNonDirectFeedthrough) {
DiagramBuilder<double> builder;

auto integrator1 = builder.AddSystem<Integrator>(1 /* size */);
integrator1->set_name("integrator1");
auto integrator2 = builder.AddSystem<Integrator>(1 /* size */);
integrator2->set_name("integrator2");
auto integrator1 = builder.AddNamedSystem<Integrator>(
"integrator1", 1 /* size */);
auto integrator2 = builder.AddNamedSystem<Integrator>(
"integrator2, ", 1 /* size */);

builder.Connect(integrator1->get_output_port(),
integrator2->get_input_port());
Expand Down Expand Up @@ -228,10 +235,10 @@ GTEST_TEST(DiagramBuilderTest, SystemsThatAreNotAddedThrow) {

GTEST_TEST(DiagramBuilderTest, ConnectVectorToAbstractThrow) {
DiagramBuilder<double> builder;
auto vector_system = builder.AddSystem<PassThrough<double>>(1 /* size */);
vector_system->set_name("vector_system");
auto abstract_system = builder.AddSystem<PassThrough<double>>(Value<int>{});
abstract_system->set_name("abstract_system");
auto vector_system = builder.AddNamedSystem<PassThrough<double>>(
"vector_system", 1 /* size */);
auto abstract_system = builder.AddNamedSystem<PassThrough<double>>(
"abstract_system", Value<int>{});
DRAKE_EXPECT_THROWS_MESSAGE(
builder.Connect(
vector_system->get_output_port(),
Expand Down Expand Up @@ -286,10 +293,10 @@ GTEST_TEST(DiagramBuilderTest, ExportInputAbstractToVectorThrow) {

GTEST_TEST(DiagramBuilderTest, ConnectVectorSizeMismatchThrow) {
DiagramBuilder<double> builder;
auto size1_system = builder.AddSystem<PassThrough<double>>(1 /* size */);
size1_system->set_name("size1_system");
auto size2_system = builder.AddSystem<PassThrough<double>>(2 /* size */);
size2_system->set_name("size2_system");
auto size1_system = builder.AddNamedSystem<PassThrough<double>>(
"size1_system", 1 /* size */);
auto size2_system = builder.AddNamedSystem<PassThrough<double>>(
"size2_system", 2 /* size */);
DRAKE_EXPECT_THROWS_MESSAGE(
builder.Connect(
size1_system->get_output_port(),
Expand Down Expand Up @@ -328,10 +335,10 @@ GTEST_TEST(DiagramBuilderTest, ExportInputVectorSizeMismatchThrow) {

GTEST_TEST(DiagramBuilderTest, ConnectAbstractTypeMismatchThrow) {
DiagramBuilder<double> builder;
auto int_system = builder.AddSystem<PassThrough<double>>(Value<int>{});
int_system->set_name("int_system");
auto char_system = builder.AddSystem<PassThrough<double>>(Value<char>{});
char_system->set_name("char_system");
auto int_system = builder.AddNamedSystem<PassThrough<double>>(
"int_system", Value<int>{});
auto char_system = builder.AddNamedSystem<PassThrough<double>>(
"char_system", Value<char>{});
DRAKE_EXPECT_THROWS_MESSAGE(
builder.Connect(
int_system->get_output_port(),
Expand Down Expand Up @@ -460,15 +467,11 @@ GTEST_TEST(DiagramBuilderTest, DefaultPortNamesAreUniqueTest2) {
DiagramBuilder<double> builder;

// This time, we assign system names manually.
auto sink1 = builder.AddSystem<Sink<double>>();
sink1->set_name("sink1");
auto sink2 = builder.AddSystem<Sink<double>>();
sink2->set_name("sink2");
auto sink1 = builder.AddNamedSystem<Sink<double>>("sink1");
auto sink2 = builder.AddNamedSystem<Sink<double>>("sink2");

auto source1 = builder.AddSystem<Source<double>>();
source1->set_name("source1");
auto source2 = builder.AddSystem<Source<double>>();
source2->set_name("source2");
auto source1 = builder.AddNamedSystem<Source<double>>("source1");
auto source2 = builder.AddNamedSystem<Source<double>>("source2");

const auto sink1_in = builder.ExportInput(sink1->get_input_port(0));
const auto sink2_in = builder.ExportInput(sink2->get_input_port(0));
Expand Down Expand Up @@ -566,16 +569,14 @@ GTEST_TEST(DiagramBuilderTest, DuplicateOutputPortNamesThrow) {
class DiagramBuilderSolePortsTest : public ::testing::Test {
protected:
void SetUp() override {
out1_ = builder_.AddSystem<ConstantVectorSource>(Vector1d::Ones());
out1_->set_name("constant");
in1_ = builder_.AddSystem<Sink>();
in1_->set_name("sink");
in1out1_ = builder_.AddSystem<Gain>(1.0 /* gain */, 1 /* size */);
in1out1_->set_name("gain");
in2out1_ = builder_.AddSystem<Adder>(2 /* inputs */, 1 /* size */);
in2out1_->set_name("adder");
in1out2_ = builder_.AddSystem<Demultiplexer>(2 /* size */);
in1out2_->set_name("demux");
out1_ = builder_.AddNamedSystem<ConstantVectorSource>(
"constant", Vector1d::Ones());
in1_ = builder_.AddNamedSystem<Sink>("sink");
in1out1_ = builder_.AddNamedSystem<Gain>(
"gain", 1.0 /* gain */, 1 /* size */);
in2out1_ = builder_.AddNamedSystem<Adder>(
"adder", 2 /* inputs */, 1 /* size */);
in1out2_ = builder_.AddNamedSystem<Demultiplexer>("demux", 2 /* size */);
}

DiagramBuilder<double> builder_;
Expand Down Expand Up @@ -626,10 +627,10 @@ TEST_F(DiagramBuilderSolePortsTest, TooManySrcInputs) {
// Test for GetSystems and GetMutableSystems.
GTEST_TEST(DiagramBuilderTest, GetMutableSystems) {
DiagramBuilder<double> builder;
auto adder1 = builder.AddSystem<Adder>(1 /* inputs */, 1 /* size */);
adder1->set_name("adder1");
auto adder2 = builder.AddSystem<Adder>(1 /* inputs */, 1 /* size */);
adder2->set_name("adder2");
auto adder1 = builder.AddNamedSystem<Adder>(
"adder1", 1 /* inputs */, 1 /* size */);
auto adder2 = builder.AddNamedSystem<Adder>(
"adder2", 1 /* inputs */, 1 /* size */);
EXPECT_EQ((std::vector<const System<double>*>{adder1, adder2}),
builder.GetSystems());
EXPECT_EQ((std::vector<System<double>*>{adder1, adder2}),
Expand All @@ -640,10 +641,10 @@ GTEST_TEST(DiagramBuilderTest, GetMutableSystems) {
// number of ExportInput() / ExportOutput() calls.
GTEST_TEST(DiagramBuilderTest, ExportInputOutputIndex) {
DiagramBuilder<double> builder;
auto adder1 = builder.AddSystem<Adder>(3 /* inputs */, 1 /* size */);
adder1->set_name("adder1");
auto adder2 = builder.AddSystem<Adder>(1 /* inputs */, 1 /* size */);
adder2->set_name("adder2");
auto adder1 = builder.AddNamedSystem<Adder>(
"adder1", 3 /* inputs */, 1 /* size */);
auto adder2 = builder.AddNamedSystem<Adder>(
"adder2", 1 /* inputs */, 1 /* size */);

EXPECT_EQ(builder.ExportInput(
adder1->get_input_port(0)), 0 /* exported input port id */);
Expand Down

0 comments on commit aa4de29

Please sign in to comment.