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

Python gc fixes prototype #22022

Draft
wants to merge 10 commits into
base: master
Choose a base branch
from
1 change: 1 addition & 0 deletions bindings/pydrake/examples/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -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 = [
Expand Down
6 changes: 3 additions & 3 deletions bindings/pydrake/examples/examples_py_acrobot.cc
Original file line number Diff line number Diff line change
@@ -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"
Expand Down Expand Up @@ -161,8 +162,7 @@ void DefineExamplesAcrobot(py::module m) {
geometry::SceneGraph<double>*>(&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",
Expand All @@ -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);
}
Expand Down
5 changes: 3 additions & 2 deletions bindings/pydrake/examples/examples_py_compass_gait.cc
Original file line number Diff line number Diff line change
@@ -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"
Expand Down Expand Up @@ -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",
Expand All @@ -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);
}
Expand Down
3 changes: 2 additions & 1 deletion bindings/pydrake/examples/examples_py_pendulum.cc
Original file line number Diff line number Diff line change
@@ -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"
Expand Down Expand Up @@ -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);
}
Expand Down
3 changes: 2 additions & 1 deletion bindings/pydrake/examples/examples_py_quadrotor.cc
Original file line number Diff line number Diff line change
@@ -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"
Expand Down Expand Up @@ -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"),
Expand Down
5 changes: 3 additions & 2 deletions bindings/pydrake/examples/examples_py_rimless_wheel.cc
Original file line number Diff line number Diff line change
@@ -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"
Expand Down Expand Up @@ -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",
Expand All @@ -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);
}
Expand Down
1 change: 1 addition & 0 deletions bindings/pydrake/geometry/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -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",
Expand Down
13 changes: 7 additions & 6 deletions bindings/pydrake/geometry/geometry_py_visualizers.cc
Original file line number Diff line number Diff line change
Expand Up @@ -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"
Expand Down Expand Up @@ -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<systems::DiagramBuilder<T>*,
Expand All @@ -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<T>::DispatchLoadMessage, py::arg("scene_graph"),
Expand Down Expand Up @@ -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)
Expand All @@ -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
Expand Down
2 changes: 1 addition & 1 deletion bindings/pydrake/lcm_py.cc
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@ PYBIND11_MODULE(lcm, m) {
{
using Class = DrakeLcmInterface;
constexpr auto& cls_doc = doc.DrakeLcmInterface;
py::class_<Class>(m, "DrakeLcmInterface", cls_doc.doc)
py::class_<Class>(m, "DrakeLcmInterface", py::dynamic_attr(), cls_doc.doc)
.def("get_lcm_url", &DrakeLcmInterface::get_lcm_url,
cls_doc.get_lcm_url.doc)
.def(
Expand Down
1 change: 1 addition & 0 deletions bindings/pydrake/manipulation/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -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__",
Expand Down
7 changes: 4 additions & 3 deletions bindings/pydrake/manipulation/manipulation_py_kuka_iiwa.cc
Original file line number Diff line number Diff line change
@@ -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"
Expand Down Expand Up @@ -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);
}

Expand All @@ -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);
}
}

Expand Down
2 changes: 2 additions & 0 deletions bindings/pydrake/manipulation/manipulation_py_schunk_wsg.cc
Original file line number Diff line number Diff line change
Expand Up @@ -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"),
Expand Down
1 change: 1 addition & 0 deletions bindings/pydrake/manipulation/manipulation_py_util.cc
Original file line number Diff line number Diff line change
Expand Up @@ -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"),
Expand Down
2 changes: 2 additions & 0 deletions bindings/pydrake/multibody/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -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",
Expand Down Expand Up @@ -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",
],
Expand Down
7 changes: 4 additions & 3 deletions bindings/pydrake/multibody/meshcat_py.cc
Original file line number Diff line number Diff line change
@@ -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"
Expand Down Expand Up @@ -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)
Expand All @@ -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
Expand All @@ -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
Expand Down
36 changes: 13 additions & 23 deletions bindings/pydrake/multibody/plant_py.cc
Original file line number Diff line number Diff line change
Expand Up @@ -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"
Expand Down Expand Up @@ -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<T>* builder,
[](systems::DiagramBuilder<T>* builder,
const AddMultibodyPlantSceneGraphResult<T>& 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);
};

Expand Down Expand Up @@ -1544,7 +1534,7 @@ void DoScalarDependentDefinitions(py::module m, T) {
py::arg("X_BodyWing") = math::RigidTransform<double>::Identity(),
py::arg("fluid_density") = Wing<T>::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);
}

Expand Down Expand Up @@ -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);

{
Expand Down
2 changes: 2 additions & 0 deletions bindings/pydrake/planning/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -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",
],
)

Expand Down
8 changes: 1 addition & 7 deletions bindings/pydrake/planning/planning_py_robot_diagram.cc
Original file line number Diff line number Diff line change
Expand Up @@ -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{});
Expand Down
Loading