Skip to content

Commit

Permalink
py systems: Add keep_alive cycle to DiagramBuilder.AddSystem (#14356)
Browse files Browse the repository at this point in the history
This is a workaround to ensure we propagate keep_alive relationships

Resolves #14355
  • Loading branch information
EricCousineau-TRI authored Nov 19, 2020
1 parent aa02a6b commit b1d0617
Show file tree
Hide file tree
Showing 3 changed files with 54 additions and 3 deletions.
5 changes: 5 additions & 0 deletions bindings/pydrake/systems/framework_py_semantics.cc
Original file line number Diff line number Diff line change
Expand Up @@ -457,6 +457,11 @@ void DefineFrameworkPySemantics(py::module m) {
return self->AddSystem(std::move(system));
},
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<2, 1>(), doc.DiagramBuilder.AddSystem.doc)
.def("empty", &DiagramBuilder<T>::empty, doc.DiagramBuilder.empty.doc)
Expand Down
46 changes: 45 additions & 1 deletion bindings/pydrake/systems/test/controllers_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@
PidControlledSystem,
PidController,
)
from pydrake.systems.framework import InputPortSelection
from pydrake.systems.framework import DiagramBuilder, InputPortSelection
from pydrake.systems.primitives import Integrator, LinearSystem
from pydrake.trajectories import Trajectory

Expand Down Expand Up @@ -194,6 +194,50 @@ def test_inverse_dynamics_controller(self):
self.assertTrue(np.allclose(output.get_vector_data(0).CopyToVector(),
tau_id))

def test_issue14355(self):
"""
DiagramBuilder.AddSystem() may not propagate keep alive relationships.
We use this test to show resolution at a known concrete point of
failure.
https://github.com/RobotLocomotion/drake/issues/14355
"""

def make_diagram():
# Use a nested function to ensure that all locals get garbage
# collected quickly.

# Construct a trivial plant and ID controller.
# N.B. We explicitly do *not* add this plant to the diagram.
controller_plant = MultibodyPlant(time_step=0.002)
controller_plant.Finalize()
builder = DiagramBuilder()
controller = builder.AddSystem(
InverseDynamicsController(
controller_plant,
kp=[],
ki=[],
kd=[],
has_reference_acceleration=False,
)
)
# Forward ports for ease of testing.
builder.ExportInput(
controller.get_input_port_estimated_state(), "x_estimated")
builder.ExportInput(
controller.get_input_port_desired_state(), "x_desired")
builder.ExportOutput(controller.get_output_port_control(), "u")
diagram = builder.Build()
return diagram

diagram = make_diagram()
# N.B. Without the workaround for #14355, we get a segfault when
# creating the context.
context = diagram.CreateDefaultContext()
diagram.GetInputPort("x_estimated").FixValue(context, [])
diagram.GetInputPort("x_desired").FixValue(context, [])
u = diagram.GetOutputPort("u").Eval(context)
np.testing.assert_equal(u, [])

def test_pid_controlled_system(self):
controllers = [
PidControlledSystem(plant=PendulumPlant(), kp=1., ki=0.,
Expand Down
6 changes: 4 additions & 2 deletions bindings/pydrake/systems/test/lifetime_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -64,8 +64,10 @@ def test_ownership_diagram(self):
self.assertFalse(info.deleted)
self.assertTrue(system is not None)
del system
# Upon removing this reference, everything should be cleared up.
self.assertTrue(info.deleted)
# Upon removing this reference, everything should have been cleared up.
# However, since we work around #14355 by inducing a keep_alive cycle,
# it will not be deleted.
self.assertFalse(info.deleted)

def test_ownership_multiple_containers(self):
info = Info()
Expand Down

0 comments on commit b1d0617

Please sign in to comment.