diff --git a/bindings/pydrake/examples/BUILD.bazel b/bindings/pydrake/examples/BUILD.bazel index 27ccc5cf34ee..f27cf2c93277 100644 --- a/bindings/pydrake/examples/BUILD.bazel +++ b/bindings/pydrake/examples/BUILD.bazel @@ -25,6 +25,7 @@ drake_pybind_library( cc_deps = [ "//bindings/pydrake:documentation_pybind", "//bindings/pydrake/common:deprecation_pybind", + "//bindings/pydrake/common:ref_cycle_pybind", ], cc_so_name = "__init__", cc_srcs = [ diff --git a/bindings/pydrake/examples/examples_py_acrobot.cc b/bindings/pydrake/examples/examples_py_acrobot.cc index 8aacf38247fe..247b0a1d9c77 100644 --- a/bindings/pydrake/examples/examples_py_acrobot.cc +++ b/bindings/pydrake/examples/examples_py_acrobot.cc @@ -1,3 +1,4 @@ +#include "drake/bindings/pydrake/common/ref_cycle_pybind.h" #include "drake/bindings/pydrake/documentation_pybind.h" #include "drake/bindings/pydrake/examples/examples_py.h" #include "drake/bindings/pydrake/pydrake_pybind.h" @@ -161,8 +162,7 @@ void DefineExamplesAcrobot(py::module m) { geometry::SceneGraph*>(&AcrobotGeometry::AddToBuilder), py::arg("builder"), py::arg("acrobot_state_port"), py::arg("acrobot_params"), py::arg("scene_graph"), - // Keep alive, ownership: `return` keeps `builder` alive. - py::keep_alive<0, 1>(), + internal::ref_cycle<0, 1>(), // See #11531 for why `py_rvp::reference` is needed. py_rvp::reference, doc.AcrobotGeometry.AddToBuilder.doc_4args) .def_static("AddToBuilder", @@ -172,7 +172,7 @@ void DefineExamplesAcrobot(py::module m) { py::arg("builder"), py::arg("acrobot_state_port"), py::arg("scene_graph"), // Keep alive, ownership: `return` keeps `builder` alive. - py::keep_alive<0, 1>(), + internal::ref_cycle<0, 1>(), // See #11531 for why `py_rvp::reference` is needed. py_rvp::reference, doc.AcrobotGeometry.AddToBuilder.doc_3args); } diff --git a/bindings/pydrake/examples/examples_py_compass_gait.cc b/bindings/pydrake/examples/examples_py_compass_gait.cc index dc1c99fa1157..3f3d22b8eda0 100644 --- a/bindings/pydrake/examples/examples_py_compass_gait.cc +++ b/bindings/pydrake/examples/examples_py_compass_gait.cc @@ -1,3 +1,4 @@ +#include "drake/bindings/pydrake/common/ref_cycle_pybind.h" #include "drake/bindings/pydrake/documentation_pybind.h" #include "drake/bindings/pydrake/examples/examples_py.h" #include "drake/bindings/pydrake/pydrake_pybind.h" @@ -93,7 +94,7 @@ void DefineExamplesCompassGait(py::module m) { py::arg("builder"), py::arg("floating_base_state_port"), py::arg("compass_gait_params"), py::arg("scene_graph"), // Keep alive, ownership: `return` keeps `builder` alive. - py::keep_alive<0, 1>(), + internal::ref_cycle<0, 1>(), // See #11531 for why `py_rvp::reference` is needed. py_rvp::reference, doc.CompassGaitGeometry.AddToBuilder.doc_4args) .def_static("AddToBuilder", @@ -104,7 +105,7 @@ void DefineExamplesCompassGait(py::module m) { py::arg("builder"), py::arg("floating_base_state_port"), py::arg("scene_graph"), // Keep alive, ownership: `return` keeps `builder` alive. - py::keep_alive<0, 1>(), + internal::ref_cycle<0, 1>(), // See #11531 for why `py_rvp::reference` is needed. py_rvp::reference, doc.CompassGaitGeometry.AddToBuilder.doc_3args); } diff --git a/bindings/pydrake/examples/examples_py_pendulum.cc b/bindings/pydrake/examples/examples_py_pendulum.cc index 2e7c953b9a0a..7b070f5a6b70 100644 --- a/bindings/pydrake/examples/examples_py_pendulum.cc +++ b/bindings/pydrake/examples/examples_py_pendulum.cc @@ -1,3 +1,4 @@ +#include "drake/bindings/pydrake/common/ref_cycle_pybind.h" #include "drake/bindings/pydrake/documentation_pybind.h" #include "drake/bindings/pydrake/examples/examples_py.h" #include "drake/bindings/pydrake/pydrake_pybind.h" @@ -106,7 +107,7 @@ void DefineExamplesPendulum(py::module m) { py::arg("builder"), py::arg("pendulum_state_port"), py::arg("scene_graph"), // Keep alive, ownership: `return` keeps `builder` alive. - py::keep_alive<0, 1>(), + internal::ref_cycle<0, 1>(), // See #11531 for why `py_rvp::reference` is needed. py_rvp::reference, doc.PendulumGeometry.AddToBuilder.doc); } diff --git a/bindings/pydrake/examples/examples_py_quadrotor.cc b/bindings/pydrake/examples/examples_py_quadrotor.cc index 545034feb83b..b77c5f85e6b6 100644 --- a/bindings/pydrake/examples/examples_py_quadrotor.cc +++ b/bindings/pydrake/examples/examples_py_quadrotor.cc @@ -1,3 +1,4 @@ +#include "drake/bindings/pydrake/common/ref_cycle_pybind.h" #include "drake/bindings/pydrake/documentation_pybind.h" #include "drake/bindings/pydrake/examples/examples_py.h" #include "drake/bindings/pydrake/pydrake_pybind.h" @@ -45,7 +46,7 @@ void DefineExamplesQuadrotor(py::module m) { py::arg("builder"), py::arg("quadrotor_state_port"), py::arg("scene_graph"), py::return_value_policy::reference, // Keep alive, ownership: `return` keeps `builder` alive. - py::keep_alive<0, 1>(), doc.QuadrotorGeometry.AddToBuilder.doc); + internal::ref_cycle<0, 1>(), doc.QuadrotorGeometry.AddToBuilder.doc); m.def("StabilizingLQRController", &StabilizingLQRController, py::arg("quadrotor_plant"), py::arg("nominal_position"), diff --git a/bindings/pydrake/examples/examples_py_rimless_wheel.cc b/bindings/pydrake/examples/examples_py_rimless_wheel.cc index 34841253adba..575b527c5aa0 100644 --- a/bindings/pydrake/examples/examples_py_rimless_wheel.cc +++ b/bindings/pydrake/examples/examples_py_rimless_wheel.cc @@ -1,3 +1,4 @@ +#include "drake/bindings/pydrake/common/ref_cycle_pybind.h" #include "drake/bindings/pydrake/documentation_pybind.h" #include "drake/bindings/pydrake/examples/examples_py.h" #include "drake/bindings/pydrake/pydrake_pybind.h" @@ -82,7 +83,7 @@ void DefineExamplesRimlessWheel(py::module m) { py::arg("builder"), py::arg("floating_base_state_port"), py::arg("rimless_wheel_params"), py::arg("scene_graph"), // Keep alive, ownership: `return` keeps `builder` alive. - py::keep_alive<0, 1>(), + internal::ref_cycle<0, 1>(), // See #11531 for why `py_rvp::reference` is needed. py_rvp::reference, doc.RimlessWheelGeometry.AddToBuilder.doc_4args) .def_static("AddToBuilder", @@ -93,7 +94,7 @@ void DefineExamplesRimlessWheel(py::module m) { py::arg("builder"), py::arg("floating_base_state_port"), py::arg("scene_graph"), // Keep alive, ownership: `return` keeps `builder` alive. - py::keep_alive<0, 1>(), + internal::ref_cycle<0, 1>(), // See #11531 for why `py_rvp::reference` is needed. py_rvp::reference, doc.RimlessWheelGeometry.AddToBuilder.doc_3args); } diff --git a/bindings/pydrake/geometry/BUILD.bazel b/bindings/pydrake/geometry/BUILD.bazel index 06133bdd6df2..b2e0bf3519a0 100644 --- a/bindings/pydrake/geometry/BUILD.bazel +++ b/bindings/pydrake/geometry/BUILD.bazel @@ -38,6 +38,7 @@ drake_pybind_library( "//bindings/pydrake/common:default_scalars_pybind", "//bindings/pydrake/common:deprecation_pybind", "//bindings/pydrake/common:identifier_pybind", + "//bindings/pydrake/common:ref_cycle_pybind", "//bindings/pydrake/common:serialize_pybind", "//bindings/pydrake/common:sorted_pair_pybind", "//bindings/pydrake/common:type_pack", diff --git a/bindings/pydrake/geometry/geometry_py_visualizers.cc b/bindings/pydrake/geometry/geometry_py_visualizers.cc index 184970d33f6f..cd700d89960d 100644 --- a/bindings/pydrake/geometry/geometry_py_visualizers.cc +++ b/bindings/pydrake/geometry/geometry_py_visualizers.cc @@ -3,6 +3,7 @@ #include "drake/bindings/pydrake/common/default_scalars_pybind.h" #include "drake/bindings/pydrake/common/deprecation_pybind.h" +#include "drake/bindings/pydrake/common/ref_cycle_pybind.h" #include "drake/bindings/pydrake/common/serialize_pybind.h" #include "drake/bindings/pydrake/common/type_pack.h" #include "drake/bindings/pydrake/common/type_safe_index_pybind.h" @@ -54,9 +55,9 @@ void DefineDrakeVisualizer(py::module m, T) { py::arg("lcm") = nullptr, py::arg("params") = DrakeVisualizerParams{}, // Keep alive, ownership: `return` keeps `builder` alive. - py::keep_alive<0, 1>(), + internal::ref_cycle<0, 1>(), // Keep alive, reference: `builder` keeps `lcm` alive. - py::keep_alive<1, 3>(), py_rvp::reference, + internal::ref_cycle<1, 3>(), py_rvp::reference, cls_doc.AddToBuilder.doc_4args_builder_scene_graph_lcm_params) .def_static("AddToBuilder", py::overload_cast*, @@ -66,9 +67,9 @@ void DefineDrakeVisualizer(py::module m, T) { py::arg("lcm") = nullptr, py::arg("params") = DrakeVisualizerParams{}, // Keep alive, ownership: `return` keeps `builder` alive. - py::keep_alive<0, 1>(), + internal::ref_cycle<0, 1>(), // Keep alive, reference: `builder` keeps `lcm` alive. - py::keep_alive<1, 3>(), py_rvp::reference, + internal::ref_cycle<1, 3>(), py_rvp::reference, cls_doc.AddToBuilder.doc_4args_builder_query_object_port_lcm_params) .def_static("DispatchLoadMessage", &DrakeVisualizer::DispatchLoadMessage, py::arg("scene_graph"), @@ -136,7 +137,7 @@ void DefineMeshcatVisualizer(py::module m, T) { py::arg("builder"), py::arg("scene_graph"), py::arg("meshcat"), py::arg("params") = MeshcatVisualizerParams{}, // Keep alive, ownership: `return` keeps `builder` alive. - py::keep_alive<0, 1>(), + internal::ref_cycle<0, 1>(), // `meshcat` is a shared_ptr, so does not need a keep_alive. py_rvp::reference, cls_doc.AddToBuilder.doc_4args_builder_scene_graph_meshcat_params) @@ -147,7 +148,7 @@ void DefineMeshcatVisualizer(py::module m, T) { py::arg("builder"), py::arg("query_object_port"), py::arg("meshcat"), py::arg("params") = MeshcatVisualizerParams{}, // Keep alive, ownership: `return` keeps `builder` alive. - py::keep_alive<0, 1>(), + internal::ref_cycle<0, 1>(), // `meshcat` is a shared_ptr, so does not need a keep_alive. py_rvp::reference, cls_doc.AddToBuilder diff --git a/bindings/pydrake/lcm_py.cc b/bindings/pydrake/lcm_py.cc index 5d3973891638..7fb7bd6df591 100644 --- a/bindings/pydrake/lcm_py.cc +++ b/bindings/pydrake/lcm_py.cc @@ -26,7 +26,7 @@ PYBIND11_MODULE(lcm, m) { { using Class = DrakeLcmInterface; constexpr auto& cls_doc = doc.DrakeLcmInterface; - py::class_(m, "DrakeLcmInterface", cls_doc.doc) + py::class_(m, "DrakeLcmInterface", py::dynamic_attr(), cls_doc.doc) .def("get_lcm_url", &DrakeLcmInterface::get_lcm_url, cls_doc.get_lcm_url.doc) .def( diff --git a/bindings/pydrake/manipulation/BUILD.bazel b/bindings/pydrake/manipulation/BUILD.bazel index 6d02c4cf157c..c1d6e57e3245 100644 --- a/bindings/pydrake/manipulation/BUILD.bazel +++ b/bindings/pydrake/manipulation/BUILD.bazel @@ -25,6 +25,7 @@ drake_pybind_library( cc_deps = [ "//bindings/pydrake:documentation_pybind", "//bindings/pydrake/common:eigen_pybind", + "//bindings/pydrake/common:ref_cycle_pybind", "//bindings/pydrake/common:serialize_pybind", ], cc_so_name = "__init__", diff --git a/bindings/pydrake/manipulation/manipulation_py_kuka_iiwa.cc b/bindings/pydrake/manipulation/manipulation_py_kuka_iiwa.cc index dbf1089626f7..bf93d6c6cc15 100644 --- a/bindings/pydrake/manipulation/manipulation_py_kuka_iiwa.cc +++ b/bindings/pydrake/manipulation/manipulation_py_kuka_iiwa.cc @@ -1,3 +1,4 @@ +#include "drake/bindings/pydrake/common/ref_cycle_pybind.h" #include "drake/bindings/pydrake/common/serialize_pybind.h" #include "drake/bindings/pydrake/documentation_pybind.h" #include "drake/bindings/pydrake/manipulation/manipulation_py.h" @@ -180,9 +181,9 @@ void DefineManipulationKukaIiwa(py::module m) { py::arg("controller_plant"), py::arg("ext_joint_filter_tau"), py::arg("desired_iiwa_kp_gains"), py::arg("control_mode"), // Keep alive, ownership: `return` keeps `builder` alive. - py::keep_alive<0, 1>(), + internal::ref_cycle<0, 1>(), // Keep alive, reference: `builder` keeps `controller_plant` alive. - py::keep_alive<1, 4>(), py_rvp::reference, + internal::ref_cycle<1, 4>(), py_rvp::reference, cls_doc.AddToBuilder.doc); } @@ -198,7 +199,7 @@ void DefineManipulationKukaIiwa(py::module m) { py::arg("desired_iiwa_kp_gains") = std::nullopt, py::arg("control_mode") = IiwaControlMode::kPositionAndTorque, // Keep alive, reference: `builder` keeps `controller_plant` alive. - py::keep_alive<5, 3>(), doc.BuildIiwaControl.doc); + internal::ref_cycle<5, 3>(), doc.BuildIiwaControl.doc); } } diff --git a/bindings/pydrake/manipulation/manipulation_py_schunk_wsg.cc b/bindings/pydrake/manipulation/manipulation_py_schunk_wsg.cc index a9bdb54ce894..f16166e41060 100644 --- a/bindings/pydrake/manipulation/manipulation_py_schunk_wsg.cc +++ b/bindings/pydrake/manipulation/manipulation_py_schunk_wsg.cc @@ -122,11 +122,13 @@ void DefineManipulationSchunkWsg(py::module m) { { using T = double; + // XXX probably needs annotations m.def("ApplyDriverConfig", &manipulation::schunk_wsg::ApplyDriverConfig, py::arg("driver_config"), py::arg("model_instance_name"), py::arg("sim_plant"), py::arg("models_from_directives"), py::arg("lcms"), py::arg("builder"), doc.ApplyDriverConfig.doc); + // XXX probably needs annotations m.def("BuildSchunkWsgControl", &manipulation::schunk_wsg::BuildSchunkWsgControl, py::arg("plant"), py::arg("wsg_instance"), py::arg("lcm"), py::arg("builder"), diff --git a/bindings/pydrake/manipulation/manipulation_py_util.cc b/bindings/pydrake/manipulation/manipulation_py_util.cc index 33bc083d3a1c..4bda82c0cb69 100644 --- a/bindings/pydrake/manipulation/manipulation_py_util.cc +++ b/bindings/pydrake/manipulation/manipulation_py_util.cc @@ -26,6 +26,7 @@ void DefineManipulationUtil(py::module m) { } { + // XXX probably needs annotations m.def("ApplyDriverConfig", &ApplyDriverConfig, py::arg("driver_config"), py::arg("model_instance_name"), py::arg("sim_plant"), py::arg("models_from_directives"), py::arg("lcms"), py::arg("builder"), diff --git a/bindings/pydrake/multibody/BUILD.bazel b/bindings/pydrake/multibody/BUILD.bazel index 156e1c132da8..342fe7cef67c 100644 --- a/bindings/pydrake/multibody/BUILD.bazel +++ b/bindings/pydrake/multibody/BUILD.bazel @@ -131,6 +131,7 @@ drake_pybind_library( "//bindings/pydrake/common:deprecation_pybind", "//bindings/pydrake/common:eigen_pybind", "//bindings/pydrake/common:identifier_pybind", + "//bindings/pydrake/common:ref_cycle_pybind", "//bindings/pydrake/common:serialize_pybind", "//bindings/pydrake/common:type_pack", "//bindings/pydrake/common:type_safe_index_pybind", @@ -172,6 +173,7 @@ drake_pybind_library( "//bindings/pydrake:documentation_pybind", "//bindings/pydrake/common:cpp_template_pybind", "//bindings/pydrake/common:default_scalars_pybind", + "//bindings/pydrake/common:ref_cycle_pybind", "//bindings/pydrake/common:serialize_pybind", "//bindings/pydrake/common:type_pack", ], diff --git a/bindings/pydrake/multibody/meshcat_py.cc b/bindings/pydrake/multibody/meshcat_py.cc index 8c0d8b5e4cf4..d3c4e14ac331 100644 --- a/bindings/pydrake/multibody/meshcat_py.cc +++ b/bindings/pydrake/multibody/meshcat_py.cc @@ -1,5 +1,6 @@ #include "drake/bindings/pydrake/common/cpp_template_pybind.h" #include "drake/bindings/pydrake/common/default_scalars_pybind.h" +#include "drake/bindings/pydrake/common/ref_cycle_pybind.h" #include "drake/bindings/pydrake/common/serialize_pybind.h" #include "drake/bindings/pydrake/common/type_pack.h" #include "drake/bindings/pydrake/documentation_pybind.h" @@ -130,7 +131,7 @@ void DoScalarDependentDefinitions(py::module m, T) { py::arg("builder"), py::arg("plant"), py::arg("meshcat"), py::arg("params") = ContactVisualizerParams{}, // Keep alive, ownership: `return` keeps `builder` alive. - py::keep_alive<0, 1>(), + internal::ref_cycle<0, 1>(), // `meshcat` is a shared_ptr, so does not need a keep_alive. py_rvp::reference, cls_doc.AddToBuilder.doc_4args_builder_plant_meshcat_params) @@ -143,7 +144,7 @@ void DoScalarDependentDefinitions(py::module m, T) { py::arg("query_object_port"), py::arg("meshcat"), py::arg("params") = ContactVisualizerParams{}, // Keep alive, ownership: `return` keeps `builder` alive. - py::keep_alive<0, 1>(), + internal::ref_cycle<0, 1>(), // `meshcat` is a shared_ptr, so does not need a keep_alive. py_rvp::reference, cls_doc.AddToBuilder @@ -156,7 +157,7 @@ void DoScalarDependentDefinitions(py::module m, T) { py::arg("builder"), py::arg("contact_results_port"), py::arg("meshcat"), py::arg("params") = ContactVisualizerParams{}, // Keep alive, ownership: `return` keeps `builder` alive. - py::keep_alive<0, 1>(), + internal::ref_cycle<0, 1>(), // `meshcat` is a shared_ptr, so does not need a keep_alive. py_rvp::reference, cls_doc.AddToBuilder diff --git a/bindings/pydrake/multibody/plant_py.cc b/bindings/pydrake/multibody/plant_py.cc index 3204186e5e19..ca0e06763228 100644 --- a/bindings/pydrake/multibody/plant_py.cc +++ b/bindings/pydrake/multibody/plant_py.cc @@ -3,6 +3,7 @@ #include "drake/bindings/pydrake/common/deprecation_pybind.h" #include "drake/bindings/pydrake/common/eigen_pybind.h" #include "drake/bindings/pydrake/common/identifier_pybind.h" +#include "drake/bindings/pydrake/common/ref_cycle_pybind.h" #include "drake/bindings/pydrake/common/serialize_pybind.h" #include "drake/bindings/pydrake/common/type_pack.h" #include "drake/bindings/pydrake/common/value_pybind.h" @@ -1374,28 +1375,17 @@ void DoScalarDependentDefinitions(py::module m, T) { } { - // TODO(eric.cousineau): Figure out why we need to use this to explicit - // keep-alive vs. annotating the return tuple with `py::keep_alive()`. - // Most likely due to a bug in our fork of pybind11 for handling of - // unique_ptr<> arguments and keep_alive<> behavior for objects that are - // not yet registered with pybind11 (#11046). - auto cast_workaround = [](auto&& nurse, py::object patient_py) { - // Cast to ensure we have the object registered. - py::object nurse_py = py::cast(nurse, py_rvp::reference); - // Directly leverage pybind11's keep alive mechanism. - py::detail::keep_alive_impl(nurse_py, patient_py); - return nurse_py; - }; - auto result_to_tuple = - [cast_workaround](systems::DiagramBuilder* builder, + [](systems::DiagramBuilder* builder, const AddMultibodyPlantSceneGraphResult& pair) { py::object builder_py = py::cast(builder, py_rvp::reference); - // Keep alive, ownership: `plant` keeps `builder` alive. - py::object plant_py = cast_workaround(pair.plant, builder_py); - // Keep alive, ownership: `scene_graph` keeps `builder` alive. + py::object plant_py = py::cast(pair.plant, py_rvp::reference); py::object scene_graph_py = - cast_workaround(pair.scene_graph, builder_py); + py::cast(pair.scene_graph, py_rvp::reference); + internal::make_arbitrary_ref_cycle( + builder_py, plant_py, "AddMultibodyPlantSceneGraphResult.plant"); + internal::make_arbitrary_ref_cycle(builder_py, scene_graph_py, + "AddMultibodyPlantSceneGraphResult.scene_graph"); return py::make_tuple(plant_py, scene_graph_py); }; @@ -1544,7 +1534,7 @@ void DoScalarDependentDefinitions(py::module m, T) { py::arg("X_BodyWing") = math::RigidTransform::Identity(), py::arg("fluid_density") = Wing::kDefaultFluidDensity, // Keep alive, ownership: `return` keeps `builder` alive. - py::keep_alive<0, 1>(), py_rvp::reference, + internal::ref_cycle<0, 1>(), py_rvp::reference, cls_doc.AddToBuilder.doc); } @@ -1599,13 +1589,13 @@ PYBIND11_MODULE(plant, m) { py::arg("lcm") = nullptr, py::arg("publish_period") = std::nullopt, py_rvp::reference, // Keep alive, ownership: `return` keeps `builder` alive. - py::keep_alive<0, 1>(), + internal::ref_cycle<0, 1>(), // Keep alive, transitive: `plant` keeps `builder` alive. - py::keep_alive<2, 1>(), + internal::ref_cycle<2, 1>(), // Keep alive, transitive: `scene_graph` keeps `builder` alive. - py::keep_alive<3, 1>(), + internal::ref_cycle<3, 1>(), // Keep alive, transitive: `lcm` keeps `builder` alive. - py::keep_alive<4, 1>(), + internal::ref_cycle<4, 1>(), doc.ConnectContactResultsToDrakeVisualizer.doc_5args); { diff --git a/bindings/pydrake/planning/BUILD.bazel b/bindings/pydrake/planning/BUILD.bazel index 23168b282df5..e926e13b3757 100644 --- a/bindings/pydrake/planning/BUILD.bazel +++ b/bindings/pydrake/planning/BUILD.bazel @@ -96,6 +96,8 @@ drake_py_unittest( deps = [ ":planning", "//bindings/pydrake/common/test_utilities:numpy_compare_py", + "//bindings/pydrake/systems:analysis_py", + "//bindings/pydrake/systems:controllers_py", ], ) diff --git a/bindings/pydrake/planning/planning_py_robot_diagram.cc b/bindings/pydrake/planning/planning_py_robot_diagram.cc index 97fe087005af..22b272425700 100644 --- a/bindings/pydrake/planning/planning_py_robot_diagram.cc +++ b/bindings/pydrake/planning/planning_py_robot_diagram.cc @@ -79,13 +79,7 @@ void DefinePlanningRobotDiagram(py::module m) { cls_doc.scene_graph.doc_0args_nonconst) .def("IsDiagramBuilt", &Class::IsDiagramBuilt, cls_doc.IsDiagramBuilt.doc) - .def("Build", &Class::Build, - // Keep alive, ownership (tr.): `self` keeps `return` alive. - // Any prior reference access to our owned systems (e.g., plant()) - // must remain valid, so the RobotDiagram cannot be destroyed - // until the builder (and all of its internal references) are - // finished. - py::keep_alive<1, 0>(), cls_doc.Build.doc); + .def("Build", &Class::Build, cls_doc.Build.doc); } }; type_visit(bind_common_scalar_types, CommonScalarPack{}); diff --git a/bindings/pydrake/planning/test/robot_diagram_test.py b/bindings/pydrake/planning/test/robot_diagram_test.py index 8249a7d6a306..021ca3f37fac 100644 --- a/bindings/pydrake/planning/test/robot_diagram_test.py +++ b/bindings/pydrake/planning/test/robot_diagram_test.py @@ -1,12 +1,16 @@ import pydrake.planning as mut +import gc import unittest +import numpy as np + from pydrake.common import FindResourceOrThrow from pydrake.common.test_utilities import numpy_compare from pydrake.geometry import SceneGraph_ from pydrake.multibody.parsing import Parser from pydrake.multibody.plant import MultibodyPlant_, MultibodyPlantConfig +from pydrake.systems.controllers import InverseDynamicsController from pydrake.systems.framework import Context_, DiagramBuilder_ @@ -68,3 +72,50 @@ def test_robot_diagram(self, T): self.assertIsInstance( dut.scene_graph_context(root_context=root_context), Context_[T]) + + def test_issue14355_robot(self): + """ + XXX rewrite doc + 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_[float](time_step=0.002) + controller_plant.Finalize() + builder = mut.RobotDiagramBuilder() + controller = builder.builder().AddSystem( + InverseDynamicsController( + controller_plant, + kp=[], + ki=[], + kd=[], + has_reference_acceleration=False, + ) + ) + # Forward ports for ease of testing. + builder.builder().ExportInput( + controller.get_input_port_estimated_state(), "x_estimated") + builder.builder().ExportInput( + controller.get_input_port_desired_state(), "x_desired") + builder.builder().ExportOutput( + controller.get_output_port_control(), "u") + diagram = builder.Build() + return diagram + + diagram = make_diagram() + gc.collect() + # 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, []) diff --git a/bindings/pydrake/systems/BUILD.bazel b/bindings/pydrake/systems/BUILD.bazel index 5f93f193aa11..565375ca3519 100644 --- a/bindings/pydrake/systems/BUILD.bazel +++ b/bindings/pydrake/systems/BUILD.bazel @@ -48,6 +48,7 @@ drake_pybind_library( "//bindings/pydrake/common:default_scalars_pybind", "//bindings/pydrake/common:deprecation_pybind", "//bindings/pydrake/common:eigen_pybind", + "//bindings/pydrake/common:ref_cycle_pybind", "//bindings/pydrake/common:type_safe_index_pybind", "//bindings/pydrake/common:value_pybind", "//bindings/pydrake/common:wrap_pybind", @@ -82,6 +83,7 @@ drake_pybind_library( "//bindings/pydrake/common:cpp_template_pybind", "//bindings/pydrake/common:default_scalars_pybind", "//bindings/pydrake/common:eigen_pybind", + "//bindings/pydrake/common:ref_cycle_pybind", ], cc_srcs = ["primitives_py.cc"], package_info = PACKAGE_INFO, @@ -169,6 +171,7 @@ drake_pybind_library( "//bindings/pydrake/common:default_scalars_pybind", "//bindings/pydrake/common:deprecation_pybind", "//bindings/pydrake/common:eigen_pybind", + "//bindings/pydrake/common:ref_cycle_pybind", "//bindings/pydrake/common:serialize_pybind", "//bindings/pydrake/common:type_pack", "//bindings/pydrake/common:value_pybind", diff --git a/bindings/pydrake/systems/framework_py_semantics.cc b/bindings/pydrake/systems/framework_py_semantics.cc index a315c7028e4b..304fdc59e575 100644 --- a/bindings/pydrake/systems/framework_py_semantics.cc +++ b/bindings/pydrake/systems/framework_py_semantics.cc @@ -3,6 +3,7 @@ #include "drake/bindings/pydrake/common/cpp_template_pybind.h" #include "drake/bindings/pydrake/common/default_scalars_pybind.h" #include "drake/bindings/pydrake/common/eigen_pybind.h" +#include "drake/bindings/pydrake/common/ref_cycle_pybind.h" #include "drake/bindings/pydrake/common/type_safe_index_pybind.h" #include "drake/bindings/pydrake/common/wrap_pybind.h" #include "drake/bindings/pydrake/documentation_pybind.h" @@ -588,38 +589,45 @@ void DefineEventAndEventSubclasses(py::module m) { } } +template +struct BuilderLifeSupport { + static constexpr char kKey[] = "_pydrake_internal_life_support"; + + static void smuggle(DiagramBuilder* builder) { + BuilderLifeSupport::attrs(builder).emplace(kKey, py::cast(builder)); + } + + static void abandon(DiagramBuilder* builder) { + BuilderLifeSupport::attrs(builder).erase(kKey); + } + + static auto& attrs(DiagramBuilder* builder) { + return builder->get_mutable_life_support().attributes; + } +}; + template void DoDefineFrameworkDiagramBuilder(py::module m) { - DefineTemplateClassWithDefault>( - m, "DiagramBuilder", GetPyParam(), doc.DiagramBuilder.doc) + DefineTemplateClassWithDefault>(m, "DiagramBuilder", + GetPyParam(), doc.DiagramBuilder.doc, std::nullopt, py::dynamic_attr()) .def(py::init<>(), doc.DiagramBuilder.ctor.doc) .def( "AddSystem", [](DiagramBuilder* self, unique_ptr> system) { + BuilderLifeSupport::smuggle(self); 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) + py::arg("system"), internal::ref_cycle<1, 2>(), + doc.DiagramBuilder.AddSystem.doc) .def( "AddNamedSystem", [](DiagramBuilder* self, std::string& name, unique_ptr> system) { + BuilderLifeSupport::smuggle(self); 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) + py::arg("name"), py::arg("system"), internal::ref_cycle<1, 3>(), + doc.DiagramBuilder.AddNamedSystem.doc) .def("RemoveSystem", &DiagramBuilder::RemoveSystem, py::arg("system"), doc.DiagramBuilder.RemoveSystem.doc) .def("empty", &DiagramBuilder::empty, doc.DiagramBuilder.empty.doc) @@ -694,12 +702,21 @@ void DoDefineFrameworkDiagramBuilder(py::module m) { .def("ExportOutput", &DiagramBuilder::ExportOutput, py::arg("output"), py::arg("name") = kUseDefaultName, py_rvp::reference_internal, doc.DiagramBuilder.ExportOutput.doc) - .def("Build", &DiagramBuilder::Build, - // Keep alive, ownership (tr.): `self` keeps `return` alive. - py::keep_alive<1, 0>(), doc.DiagramBuilder.Build.doc) - .def("BuildInto", &DiagramBuilder::BuildInto, py::arg("target"), - // Keep alive, ownership (tr.): `target` keeps `self` alive. - py::keep_alive<2, 1>(), doc.DiagramBuilder.BuildInto.doc) + .def( + "Build", + [](DiagramBuilder* self) { + BuilderLifeSupport::abandon(self); + return self->Build(); + }, + internal::ref_cycle<0, 1>(), doc.DiagramBuilder.Build.doc) + .def( + "BuildInto", + [](DiagramBuilder* self, Diagram* target) { + BuilderLifeSupport::abandon(self); + self->BuildInto(target); + }, + internal::ref_cycle<1, 2>(), py::arg("target"), + doc.DiagramBuilder.BuildInto.doc) .def("IsConnectedOrExported", &DiagramBuilder::IsConnectedOrExported, py::arg("port"), doc.DiagramBuilder.IsConnectedOrExported.doc) .def("num_input_ports", &DiagramBuilder::num_input_ports, @@ -1116,6 +1133,7 @@ void DefineDiscreteValues(py::module m) { }, doc.DiscreteValues.operator_array.doc_1args_idx_nonconst); } + } // namespace void DefineFrameworkDiagramBuilder(py::module m) { diff --git a/bindings/pydrake/systems/framework_py_systems.cc b/bindings/pydrake/systems/framework_py_systems.cc index 8ff30a6f95c4..363b80a619ef 100644 --- a/bindings/pydrake/systems/framework_py_systems.cc +++ b/bindings/pydrake/systems/framework_py_systems.cc @@ -302,8 +302,9 @@ struct Impl { // TODO(eric.cousineau): Show constructor, but somehow make sure `pybind11` // knows this is abstract? auto system_cls = - DefineTemplateClassWithDefault, SystemBase, PySystem>( - m, "System", GetPyParam(), doc.System.doc); + DefineTemplateClassWithDefault, SystemBase, PySystem>(m, + "System", GetPyParam(), doc.System.doc, std::nullopt, + py::dynamic_attr()); system_cls // Resource allocation and initialization. .def("AllocateContext", &System::AllocateContext, diff --git a/bindings/pydrake/systems/lcm_py.cc b/bindings/pydrake/systems/lcm_py.cc index 8cfb9d1b2994..0563629c8bc8 100644 --- a/bindings/pydrake/systems/lcm_py.cc +++ b/bindings/pydrake/systems/lcm_py.cc @@ -174,6 +174,7 @@ PYBIND11_MODULE(lcm, m) { py::keep_alive<1, 3>(), cls_doc.Add.doc); } + // XXX probably needs annotation m.def("ApplyLcmBusConfig", py::overload_cast< const std::map>&, @@ -246,6 +247,7 @@ PYBIND11_MODULE(lcm, m) { constexpr auto& cls_doc = doc.LcmScopeSystem; py::class_>(m, "LcmScopeSystem") .def(py::init(), py::arg("size"), cls_doc.ctor.doc) + // XXX probably needs annotation .def_static( "AddToBuilder", [](systems::DiagramBuilder* builder, diff --git a/bindings/pydrake/systems/primitives_py.cc b/bindings/pydrake/systems/primitives_py.cc index 5f974f5ab502..04b3891d2795 100644 --- a/bindings/pydrake/systems/primitives_py.cc +++ b/bindings/pydrake/systems/primitives_py.cc @@ -1,6 +1,7 @@ #include "drake/bindings/pydrake/common/cpp_template_pybind.h" #include "drake/bindings/pydrake/common/default_scalars_pybind.h" #include "drake/bindings/pydrake/common/eigen_pybind.h" +#include "drake/bindings/pydrake/common/ref_cycle_pybind.h" #include "drake/bindings/pydrake/documentation_pybind.h" #include "drake/bindings/pydrake/pydrake_pybind.h" #include "drake/systems/primitives/adder.h" @@ -434,6 +435,7 @@ PYBIND11_MODULE(primitives, m) { return std::make_unique>(std::move(wrapped)); }), py::arg("value_to_hold"), doc.SharedPointerSystem.ctor.doc) + // XXX probably needs annotation .def_static( "AddToBuilder", [](DiagramBuilder* builder, py::object value_to_hold) { @@ -557,7 +559,7 @@ PYBIND11_MODULE(primitives, m) { &LogVectorOutput), py::arg("src"), py::arg("builder"), py::arg("publish_period") = 0.0, // Keep alive, ownership: `return` keeps `builder` alive. - py::keep_alive<0, 2>(), + internal::ref_cycle<0, 2>(), // See #11531 for why `py_rvp::reference` is needed. py_rvp::reference, doc.LogVectorOutput.doc_3args); @@ -567,7 +569,7 @@ PYBIND11_MODULE(primitives, m) { py::arg("src"), py::arg("builder"), py::arg("publish_triggers"), py::arg("publish_period") = 0.0, // Keep alive, ownership: `return` keeps `builder` alive. - py::keep_alive<0, 2>(), + internal::ref_cycle<0, 2>(), // See #11531 for why `py_rvp::reference` is needed. py_rvp::reference, doc.LogVectorOutput.doc_4args); @@ -749,6 +751,7 @@ PYBIND11_MODULE(primitives, m) { py::arg("num_outputs"), py::arg("sampling_interval_sec"), doc.RandomSource.ctor.doc); + // XXX annotate??? m.def("AddRandomInputs", &AddRandomInputs, py::arg("sampling_interval_sec"), py::arg("builder"), doc.AddRandomInputs.doc) diff --git a/bindings/pydrake/systems/sensors_py_camera_config.cc b/bindings/pydrake/systems/sensors_py_camera_config.cc index 966b23b542b1..ee78dcd6ecef 100644 --- a/bindings/pydrake/systems/sensors_py_camera_config.cc +++ b/bindings/pydrake/systems/sensors_py_camera_config.cc @@ -1,3 +1,4 @@ +#include "drake/bindings/pydrake/common/ref_cycle_pybind.h" #include "drake/bindings/pydrake/common/serialize_pybind.h" #include "drake/bindings/pydrake/documentation_pybind.h" #include "drake/bindings/pydrake/systems/sensors_py.h" @@ -64,7 +65,7 @@ void DefineSensorsCameraConfig(py::module m) { py::arg("plant") = nullptr, py::arg("scene_graph") = nullptr, py::arg("lcm") = nullptr, // Keep alive, reference: `builder` keeps `lcm` alive. - py::keep_alive<2, 6>(), doc.ApplyCameraConfig.doc); + internal::ref_cycle<2, 6>(), doc.ApplyCameraConfig.doc); } } // namespace internal diff --git a/bindings/pydrake/test/memory_leak_test.py b/bindings/pydrake/test/memory_leak_test.py index 4525efb40d2c..59eb3796af54 100644 --- a/bindings/pydrake/test/memory_leak_test.py +++ b/bindings/pydrake/test/memory_leak_test.py @@ -43,7 +43,7 @@ # Developer-only configuration. -VERBOSE = False +VERBOSE = True @functools.cache @@ -316,18 +316,10 @@ def test_simple_source(self): self.do_test(dut=_dut_simple_source, count=10) def test_trivial_simulator(self): - self.do_test( - dut=_dut_trivial_simulator, - count=5, - # TODO(rpoyner-tri): Allow 0 leaks. - leaks_allowed=5, leaks_required=1) + self.do_test(dut=_dut_trivial_simulator, count=5) def test_mixed_language_simulator(self): - self.do_test( - dut=_dut_mixed_language_simulator, - count=5, - # TODO(rpoyner-tri): Allow 0 leaks. - leaks_allowed=5, leaks_required=1) + self.do_test(dut=_dut_mixed_language_simulator, count=5) def test_full_example(self): # Note: this test doesn't invoke the #14355 deliberate cycle. diff --git a/bindings/pydrake/visualization/visualization_py_config.cc b/bindings/pydrake/visualization/visualization_py_config.cc index fdde46a620e1..d01554a6b740 100644 --- a/bindings/pydrake/visualization/visualization_py_config.cc +++ b/bindings/pydrake/visualization/visualization_py_config.cc @@ -25,11 +25,13 @@ void DefineVisualizationConfig(py::module m) { } m // BR + // XXX probably needs annotation .def("ApplyVisualizationConfig", &ApplyVisualizationConfig, py::arg("config"), py::arg("builder"), py::arg("lcm_buses") = nullptr, py::arg("plant") = nullptr, py::arg("scene_graph") = nullptr, py::arg("meshcat") = nullptr, py::arg("lcm") = nullptr, doc.ApplyVisualizationConfig.doc) + // XXX probably needs annotation .def("AddDefaultVisualization", &AddDefaultVisualization, py::arg("builder"), py::arg("meshcat") = nullptr, doc.AddDefaultVisualization.doc); diff --git a/systems/framework/diagram.cc b/systems/framework/diagram.cc index 26ce40f4c28a..9b92df762704 100644 --- a/systems/framework/diagram.cc +++ b/systems/framework/diagram.cc @@ -1431,6 +1431,10 @@ Diagram::ConvertScalarType() const { // Move the new systems into the blueprint. blueprint->systems = std::move(new_systems); + // Do nothing about life_support. Since scalar conversion is effectively a + // deep copy, the lifetime extensions provided by life_support are not needed + // here. + return blueprint; } @@ -1551,6 +1555,7 @@ void Diagram::Initialize(std::unique_ptr blueprint) { connection_map_ = std::move(blueprint->connection_map); output_port_ids_ = std::move(blueprint->output_port_ids); registered_systems_ = std::move(blueprint->systems); + life_support_ = std::move(blueprint->life_support); // This cache entry just maintains temporary storage. It is only ever used // by DoCalcNextUpdateTime(). Since this declaration of the cache entry diff --git a/systems/framework/diagram.h b/systems/framework/diagram.h index 4ffaaa985d80..c802805d3358 100644 --- a/systems/framework/diagram.h +++ b/systems/framework/diagram.h @@ -1,5 +1,6 @@ #pragma once +#include #include #include #include @@ -12,6 +13,7 @@ #include "drake/common/default_scalars.h" #include "drake/common/drake_copyable.h" #include "drake/common/pointer_cast.h" +#include "drake/common/string_map.h" #include "drake/systems/framework/diagram_context.h" #include "drake/systems/framework/diagram_continuous_state.h" #include "drake/systems/framework/diagram_discrete_values.h" @@ -27,9 +29,9 @@ namespace systems { namespace internal { -/// Destroys owned systems in the reverse order they were added; this enables -/// Systems to refer to each other during destruction, in the usual "undo" -/// resource order one would expect for C++. +// Destroys owned systems in the reverse order they were added; this enables +// Systems to refer to each other during destruction, in the usual "undo" +// resource order one would expect for C++. template class OwnedSystems { public: @@ -60,6 +62,17 @@ class OwnedSystems { std::vector>> vec_; }; +// External life support data for the diagram. The data will be moved to the +// diagram at Build() time. Data stored here will have a life-cycle that is the +// union of the builder and the diagram. +// +// This mechanism is particularly useful for the Python FFI. It can be used to +// extend the lifetime of Python-wrapped systems, when the Build() call occurs +// in C++ that is not exposed to the Python bindings. +struct DiagramLifeSupport { + string_map attributes; +}; + } // namespace internal template @@ -528,6 +541,8 @@ class Diagram : public System, internal::SystemParentServiceInterface { std::map connection_map; // All of the systems to be included in the diagram. internal::OwnedSystems systems; + + internal::DiagramLifeSupport life_support; }; // Constructs a Diagram from the Blueprint that a DiagramBuilder produces. @@ -603,6 +618,8 @@ class Diagram : public System, internal::SystemParentServiceInterface { // allocated as a cache entry to avoid heap operations during simulation. CacheIndex event_times_buffer_cache_index_{}; + internal::DiagramLifeSupport life_support_; + // For all T, Diagram considers DiagramBuilder a friend, so that the // builder can set the internal state correctly. friend class DiagramBuilder; diff --git a/systems/framework/diagram_builder.cc b/systems/framework/diagram_builder.cc index fa7d209a80ff..52c5172a974b 100644 --- a/systems/framework/diagram_builder.cc +++ b/systems/framework/diagram_builder.cc @@ -681,6 +681,7 @@ std::unique_ptr::Blueprint> DiagramBuilder::Compile() { blueprint->output_port_names = output_port_names_; blueprint->connection_map = connection_map_; blueprint->systems = std::move(registered_systems_); + blueprint->life_support = std::move(life_support_); already_built_ = true; diff --git a/systems/framework/diagram_builder.h b/systems/framework/diagram_builder.h index e1acfa825414..ba9cb0390614 100644 --- a/systems/framework/diagram_builder.h +++ b/systems/framework/diagram_builder.h @@ -467,6 +467,14 @@ class DiagramBuilder { /// as more ports are exported. int num_output_ports() const; + /// (Internal use only). Returns a mutable reference to life support data for + /// the diagram. The data will be moved to the diagram at Build() time. Data + /// stored here will have a life-cycle that is the union of the builder and + /// the diagram. + internal::DiagramLifeSupport& get_mutable_life_support() { + return life_support_; + } + private: // Declares a new input to the entire Diagram, using @p model_input to // supply the data type. @p name is an optional name for the input port; if @@ -533,6 +541,8 @@ class DiagramBuilder { std::unordered_set*> systems_; // The Systems in this DiagramBuilder, in the order they were registered. internal::OwnedSystems registered_systems_; + + internal::DiagramLifeSupport life_support_; }; } // namespace systems diff --git a/systems/framework/test/diagram_test.cc b/systems/framework/test/diagram_test.cc index 82493be5269c..765aa47f051f 100644 --- a/systems/framework/test/diagram_test.cc +++ b/systems/framework/test/diagram_test.cc @@ -4084,6 +4084,35 @@ GTEST_TEST(ImplicitTimeDerivatives, DiagramProcessing) { EXPECT_EQ(residual, expected_result); } +// Life support data has a lifetime that is the union of the builder and the +// resulting diagram. +GTEST_TEST(LifeSupport, Lifetime) { + std::weak_ptr spy; + { + auto do_build = [&]() { + auto thing = std::make_shared(42); + spy = thing; + DiagramBuilder builder; + builder.get_mutable_life_support().attributes.emplace("thing", + std::move(thing)); + // Thing is living inside builder. + EXPECT_FALSE(builder.get_mutable_life_support().attributes.empty()); + EXPECT_FALSE(spy.expired()); + builder.AddSystem>(); + auto result = builder.Build(); + // Thing has been transferred to diagram. + EXPECT_TRUE(builder.get_mutable_life_support().attributes.empty()); + EXPECT_FALSE(spy.expired()); + return result; + }; + auto diagram = do_build(); + // Builder is gone; thing remains. + EXPECT_FALSE(spy.expired()); + } + // Diagram is gone; thing is now also gone. + EXPECT_TRUE(spy.expired()); +} + } // namespace } // namespace systems } // namespace drake