From 9098a07caacacfb3e48b2edbdab0dd5167817948 Mon Sep 17 00:00:00 2001 From: Rick Poyner Date: Fri, 1 Nov 2024 12:12:55 -0400 Subject: [PATCH] wip: approximate annotations for examples/ --- bindings/pydrake/examples/BUILD.bazel | 1 + bindings/pydrake/examples/examples_py_acrobot.cc | 6 +++--- bindings/pydrake/examples/examples_py_compass_gait.cc | 5 +++-- bindings/pydrake/examples/examples_py_pendulum.cc | 3 ++- bindings/pydrake/examples/examples_py_quadrotor.cc | 3 ++- bindings/pydrake/examples/examples_py_rimless_wheel.cc | 5 +++-- 6 files changed, 14 insertions(+), 9 deletions(-) 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); }