From eb6090c419297a18e09118886ffb1232a431a8a5 Mon Sep 17 00:00:00 2001 From: Jeremy Nimmer Date: Tue, 12 Mar 2024 20:34:47 -0700 Subject: [PATCH 1/6] WIP [workspace] Upgrade pybind11 to v2.11.1 --- bindings/pydrake/pydrake_pybind.h | 23 ++++++++++++++++++-- tools/workspace/pybind11/package.BUILD.bazel | 1 + tools/workspace/pybind11/repository.bzl | 11 ++++------ 3 files changed, 26 insertions(+), 9 deletions(-) diff --git a/bindings/pydrake/pydrake_pybind.h b/bindings/pydrake/pydrake_pybind.h index 655e1c95bfe8..8a4fb982ee21 100644 --- a/bindings/pydrake/pydrake_pybind.h +++ b/bindings/pydrake/pydrake_pybind.h @@ -145,8 +145,27 @@ inline void ExecuteExtraPythonCode(py::module m, bool use_subdir = false) { } \ } +/* XXX comment me */ +struct npy_format_descriptor_object { + public: + enum { value = py::detail::npy_api::NPY_OBJECT_ }; + static py::dtype dtype() { + if (auto ptr = py::detail::npy_api::get().PyArray_DescrFromType_(value)) { + return py::reinterpret_borrow(ptr); + } + py::pybind11_fail("Unsupported buffer format!"); + } + static constexpr auto name = py::detail::_("object"); +}; + } // namespace pydrake } // namespace drake -#define DRAKE_PYBIND11_NUMPY_OBJECT_DTYPE(Type) \ - PYBIND11_NUMPY_OBJECT_DTYPE(Type) +#define DRAKE_PYBIND11_NUMPY_OBJECT_DTYPE(Type) \ + namespace pybind11 { \ + namespace detail { \ + template <> \ + struct npy_format_descriptor \ + : public ::drake::pydrake::npy_format_descriptor_object {}; \ + } /* namespace pybind11 */ \ + } // namespace pydrake diff --git a/tools/workspace/pybind11/package.BUILD.bazel b/tools/workspace/pybind11/package.BUILD.bazel index 9791d50f880a..09f8877f4696 100644 --- a/tools/workspace/pybind11/package.BUILD.bazel +++ b/tools/workspace/pybind11/package.BUILD.bazel @@ -57,6 +57,7 @@ cc_library( name = "pybind11", hdrs = _HDRS, includes = ["include"], + defines = ["PYBIND11_NAMESPACE=pybind11"], deps = [ "@eigen", "@python", diff --git a/tools/workspace/pybind11/repository.bzl b/tools/workspace/pybind11/repository.bzl index 35fd1e3ef280..4e1093a2c42f 100644 --- a/tools/workspace/pybind11/repository.bzl +++ b/tools/workspace/pybind11/repository.bzl @@ -1,16 +1,13 @@ load("//tools/workspace:generate_file.bzl", "generate_file") load("//tools/workspace:github.bzl", "github_archive") -# Using the `drake` branch of this repository. -_REPOSITORY = "RobotLocomotion/pybind11" +_REPOSITORY = "pybind/pybind11" -# When upgrading this commit, check the version header within -# https://github.com/RobotLocomotion/pybind11/blob/drake/include/pybind11/detail/common.h -# and if it has changed, then update the version number in the two +# When upgrading this commit, also fix the version number in the two # pybind11-*.cmake files in the current directory to match. -_COMMIT = "1f8e0c3c4365ed01f2551d61c8ea3e558f690809" +_COMMIT = "v2.11.1" -_SHA256 = "9de2e78026ddbfbdfd3b28c60d53f8f6021a5512638478692c3677c9f6890fb6" +_SHA256 = "d475978da0cdc2d43b73f30910786759d593a9d8ee05b1b6846d1eb16c6d2e0c" def pybind11_repository( name, From a2c97409e009dd97d739f51334da83ab40102e7c Mon Sep 17 00:00:00 2001 From: Jeremy Nimmer Date: Thu, 15 Jun 2023 10:26:07 -0700 Subject: [PATCH 2/6] WIP [py lcm] Adjust CreateDefaultValue for shared_ptr semantics This still needs a unit test to show before/after correctness. --- bindings/pydrake/systems/lcm_py.cc | 11 ++++++++--- 1 file changed, 8 insertions(+), 3 deletions(-) diff --git a/bindings/pydrake/systems/lcm_py.cc b/bindings/pydrake/systems/lcm_py.cc index 8cfb9d1b2994..464e11b42b55 100644 --- a/bindings/pydrake/systems/lcm_py.cc +++ b/bindings/pydrake/systems/lcm_py.cc @@ -40,9 +40,14 @@ class PySerializerInterface : public py::wrapper { // `PySerializerInterface`). C++ implementations will use the bindings on the // interface below. - std::unique_ptr CreateDefaultValue() const override { - PYBIND11_OVERLOAD_PURE(std::unique_ptr, SerializerInterface, - CreateDefaultValue); + std::unique_ptr CreateDefaultValue() const final { + py::object value = CreateDefaultValuePython(); + return value.template cast()->Clone(); + } + + py::object CreateDefaultValuePython() const { + PYBIND11_OVERLOAD_PURE_NAME(py::object, SerializerInterface, + "CreateDefaultValue", CreateDefaultValuePython); } void Deserialize(const void* message_bytes, int message_length, From 1cd808c6222155265118597a85a5239da056a31b Mon Sep 17 00:00:00 2001 From: Jeremy Nimmer Date: Thu, 15 Jun 2023 10:26:07 -0700 Subject: [PATCH 3/6] WIP [py common] Add wrapper (copied from our fork) --- .../pydrake/geometry/geometry_py_render.cc | 4 +- bindings/pydrake/pydrake_doxygen.h | 4 +- bindings/pydrake/pydrake_pybind.h | 74 ++++++++++++++++++- .../solvers/solvers_py_mathematicalprogram.cc | 4 +- .../pydrake/systems/framework_py_systems.cc | 18 ++--- bindings/pydrake/systems/lcm_py.cc | 4 +- bindings/pydrake/trajectories_py.cc | 4 +- 7 files changed, 91 insertions(+), 21 deletions(-) diff --git a/bindings/pydrake/geometry/geometry_py_render.cc b/bindings/pydrake/geometry/geometry_py_render.cc index 3565e14b91d3..f34c0976f5f1 100644 --- a/bindings/pydrake/geometry/geometry_py_render.cc +++ b/bindings/pydrake/geometry/geometry_py_render.cc @@ -38,10 +38,10 @@ using systems::sensors::PixelType; namespace { -class PyRenderEngine : public py::wrapper { +class PyRenderEngine : public wrapper { public: using Base = RenderEngine; - using BaseWrapper = py::wrapper; + using BaseWrapper = wrapper; PyRenderEngine() : BaseWrapper() {} void UpdateViewpoint(RigidTransformd const& X_WR) override { diff --git a/bindings/pydrake/pydrake_doxygen.h b/bindings/pydrake/pydrake_doxygen.h index f49d4d8990cf..92dcbbde5729 100644 --- a/bindings/pydrake/pydrake_doxygen.h +++ b/bindings/pydrake/pydrake_doxygen.h @@ -596,8 +596,8 @@ should use the drake::pydrake::WrapToMatchInputShape function. In general, minimize the amount in which users may subclass C++ classes in Python. When you do wish to do this, ensure that you use a trampoline class in `pybind`, and ensure that the trampoline class inherits from the -`py::wrapper<>` class specific to our fork of `pybind`. This ensures that no -slicing happens with the subclassed instances. +`wrapper<>` class within pydrake. This ensures that no slicing happens with +the subclassed instances. @anchor PydrakeBazelDebug # Interactive Debugging with Bazel diff --git a/bindings/pydrake/pydrake_pybind.h b/bindings/pydrake/pydrake_pybind.h index 8a4fb982ee21..451f27df6236 100644 --- a/bindings/pydrake/pydrake_pybind.h +++ b/bindings/pydrake/pydrake_pybind.h @@ -158,6 +158,76 @@ struct npy_format_descriptor_object { static constexpr auto name = py::detail::_("object"); }; +/// Wrapper to permit lifetime of a Python instance which is derived from a C++ +/// pybind type to be managed by C++. Useful when adding virtual classes to +/// containers, where Python instance being added may be collected by Python +/// gc / refcounting. +/// @note Do NOT use the methods in this class. +template +class wrapper : public Base { + public: + using Base::Base; + + virtual ~wrapper() { delete_py_if_in_cpp(); } + + // To be used by the holder casters, by means of `wrapper_interface<>`. + // TODO(eric.cousineau): Make this private to ensure contract? + void use_cpp_lifetime(py::object&& patient) { + if (lives_in_cpp()) { + throw std::runtime_error("Instance already lives in C++"); + } + patient_ = std::move(patient); + // @note It would be nice to put `resurrect_python3` here, but this is + // called by `PyObject_CallFinalizer`, which will end up reversing its + // effect anyways. + } + + /// To be used by `move_only_holder_caster`. + py::object release_cpp_lifetime() { + if (!lives_in_cpp()) { + throw std::runtime_error("Instance does not live in C++"); + } + resurrect_python3(); + // Remove existing reference. + py::object tmp = std::move(patient_); + assert(!patient_); + return tmp; + } + + protected: + // TODO(eric.cousineau): Verify this with an example workflow. + void delete_py_if_in_cpp() { + if (lives_in_cpp()) { + // Release object. + release_cpp_lifetime(); + } + } + + // Handle PEP 442, implemented in Python3, where resurrection more than once + // is a bit more dicey. + inline void resurrect_python3() { + // Leak it as a means to stay alive for now. + // See: https://bugs.python.org/issue40240 + if (_PyGC_FINALIZED(patient_.ptr())) { + if (leaked_) { + throw std::runtime_error("__del__ called twice in Python 3.8+?"); + } + leaked_ = true; + patient_.inc_ref(); + } + } + + private: + inline bool lives_in_cpp() const { + // NOTE: This is *false* if, for whatever reason, the wrapper class is + // constructed in C++... Meh. Not gonna worry about that situation. + return static_cast(patient_); + } + + py::object patient_; + bool leaked_{false}; +}; + } // namespace pydrake } // namespace drake @@ -167,5 +237,5 @@ struct npy_format_descriptor_object { template <> \ struct npy_format_descriptor \ : public ::drake::pydrake::npy_format_descriptor_object {}; \ - } /* namespace pybind11 */ \ - } // namespace pydrake + } /* namespace detail */ \ + } /* namespace pybind11 */ diff --git a/bindings/pydrake/solvers/solvers_py_mathematicalprogram.cc b/bindings/pydrake/solvers/solvers_py_mathematicalprogram.cc index 9389f65ff8f6..05e11201f783 100644 --- a/bindings/pydrake/solvers/solvers_py_mathematicalprogram.cc +++ b/bindings/pydrake/solvers/solvers_py_mathematicalprogram.cc @@ -221,9 +221,9 @@ void SetSolverOptionBySolverType(MathematicalProgram* self, } // pybind11 trampoline class to permit overriding virtual functions in Python. -class PySolverInterface : public py::wrapper { +class PySolverInterface : public wrapper { public: - using Base = py::wrapper; + using Base = wrapper; PySolverInterface() : Base() {} diff --git a/bindings/pydrake/systems/framework_py_systems.cc b/bindings/pydrake/systems/framework_py_systems.cc index eb4f0c36230c..81737d72adfd 100644 --- a/bindings/pydrake/systems/framework_py_systems.cc +++ b/bindings/pydrake/systems/framework_py_systems.cc @@ -59,9 +59,9 @@ class SystemBasePublic : public SystemBase { // Provides a templated 'namespace'. template struct Impl { - class PySystem : public py::wrapper> { + class PySystem : public wrapper> { public: - using Base = py::wrapper>; + using Base = wrapper>; using Base::Base; // Expose protected methods for binding. using Base::DeclareInputPort; @@ -116,9 +116,9 @@ struct Impl { // documentation: // http://pybind11.readthedocs.io/en/stable/advanced/classes.html#combining-virtual-functions-and-inheritance template - class PyLeafSystemBase : public py::wrapper { + class PyLeafSystemBase : public wrapper { public: - using Base = py::wrapper; + using Base = wrapper; using Base::Base; // Trampoline virtual methods. @@ -185,9 +185,9 @@ struct Impl { // documentation: // http://pybind11.readthedocs.io/en/stable/advanced/classes.html#combining-virtual-functions-and-inheritance template - class PyDiagramBase : public py::wrapper { + class PyDiagramBase : public wrapper { public: - using Base = py::wrapper; + using Base = wrapper; using Base::Base; SystemBase::GraphvizFragment DoGetGraphvizFragment( @@ -216,9 +216,9 @@ struct Impl { using Base::DoCalcVectorTimeDerivatives; }; - class PyVectorSystem : public py::wrapper { + class PyVectorSystem : public wrapper { public: - using Base = py::wrapper; + using Base = wrapper; using Base::Base; void DoCalcVectorOutput(const Context& context, @@ -267,7 +267,7 @@ struct Impl { } }; - class PySystemVisitor : public py::wrapper> { + class PySystemVisitor : public wrapper> { public: // Trampoline virtual methods. void VisitSystem(const System& system) override { diff --git a/bindings/pydrake/systems/lcm_py.cc b/bindings/pydrake/systems/lcm_py.cc index 464e11b42b55..5391674dc255 100644 --- a/bindings/pydrake/systems/lcm_py.cc +++ b/bindings/pydrake/systems/lcm_py.cc @@ -28,9 +28,9 @@ namespace { // pybind11 trampoline class to permit overriding virtual functions in // Python. -class PySerializerInterface : public py::wrapper { +class PySerializerInterface : public wrapper { public: - using Base = py::wrapper; + using Base = wrapper; PySerializerInterface() : Base() {} diff --git a/bindings/pydrake/trajectories_py.cc b/bindings/pydrake/trajectories_py.cc index 2c652d16d6bd..5581387c2ed4 100644 --- a/bindings/pydrake/trajectories_py.cc +++ b/bindings/pydrake/trajectories_py.cc @@ -167,9 +167,9 @@ struct Impl { using Base::value; }; - class PyTrajectory : public py::wrapper { + class PyTrajectory : public wrapper { public: - using Base = py::wrapper; + using Base = wrapper; using Base::Base; // Trampoline virtual methods. From 2123a082f36a399fecc4c141dde4c716c403be09 Mon Sep 17 00:00:00 2001 From: Jeremy Nimmer Date: Thu, 15 Jun 2023 10:26:07 -0700 Subject: [PATCH 4/6] WIP [py common] Add TryCastUnique --- bindings/pydrake/common/wrap_pybind.h | 19 +++++++++++++++++++ 1 file changed, 19 insertions(+) diff --git a/bindings/pydrake/common/wrap_pybind.h b/bindings/pydrake/common/wrap_pybind.h index 0c79a205b9f8..abfb5559df4b 100644 --- a/bindings/pydrake/common/wrap_pybind.h +++ b/bindings/pydrake/common/wrap_pybind.h @@ -7,6 +7,7 @@ #include #include #include +#include #include "drake/bindings/pydrake/common/wrap_function.h" #include "drake/bindings/pydrake/pydrake_pybind.h" @@ -174,5 +175,23 @@ void DefReadUniquePtr(PyClass* cls, const char* name, cls->def_property_readonly(name, getter, doc); } +/// Casts `x` to either a unique_ptr or shared_ptr depending on +/// its refcount, no matter what the pybind11 holder type is for Class. If `x` +/// is the wrong type, throws the usual pybind11 cast error. If `x` is None, +/// returns nullptr as a unique_ptr. +template +std::variant, std::shared_ptr> TryCastUnique( + py::object&& x) { + if (x.is_none()) { + return std::unique_ptr{}; + } + if (x.ref_count() == 1) { + Class* value = x.template cast(); + x.release(); + return std::unique_ptr(value); + } + return x.template cast>(); +} + } // namespace pydrake } // namespace drake From c97eefc3d6f8397322356807a7134b6756932e19 Mon Sep 17 00:00:00 2001 From: Jeremy Nimmer Date: Thu, 15 Jun 2023 10:26:07 -0700 Subject: [PATCH 5/6] WIP [py trajectories] shared_ptr --- bindings/pydrake/trajectories_py.cc | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/bindings/pydrake/trajectories_py.cc b/bindings/pydrake/trajectories_py.cc index 5581387c2ed4..f45b5715fdbc 100644 --- a/bindings/pydrake/trajectories_py.cc +++ b/bindings/pydrake/trajectories_py.cc @@ -209,15 +209,21 @@ struct Impl { std::unique_ptr> DoMakeDerivative( int derivative_order) const override { +#if 0 PYBIND11_OVERLOAD_INT(std::unique_ptr>, Trajectory, "DoMakeDerivative", derivative_order); +#endif // If the macro did not return, use default functionality. return Base::DoMakeDerivative(derivative_order); } std::unique_ptr> Clone() const override { +#if 1 + throw std::runtime_error("PyTrajectory::Clone() is not implemented"); +#else PYBIND11_OVERLOAD_PURE( std::unique_ptr>, Trajectory, Clone); +#endif } }; From b1103e5cd87e2cb70fabf5bb24dbd8758fe2fa73 Mon Sep 17 00:00:00 2001 From: Jeremy Nimmer Date: Thu, 15 Jun 2023 10:26:07 -0700 Subject: [PATCH 6/6] WIP shared_ptr --- .../pydrake/geometry/geometry_py_render.cc | 4 ++ .../planning/planning_py_collision_checker.cc | 4 ++ bindings/pydrake/systems/analysis_py.cc | 8 +++ bindings/pydrake/systems/controllers_py.cc | 2 + .../pydrake/systems/framework_py_semantics.cc | 54 +++++++++++++------ .../pydrake/systems/framework_py_systems.cc | 6 +++ 6 files changed, 61 insertions(+), 17 deletions(-) diff --git a/bindings/pydrake/geometry/geometry_py_render.cc b/bindings/pydrake/geometry/geometry_py_render.cc index f34c0976f5f1..4321b412c8dd 100644 --- a/bindings/pydrake/geometry/geometry_py_render.cc +++ b/bindings/pydrake/geometry/geometry_py_render.cc @@ -64,7 +64,11 @@ class PyRenderEngine : public wrapper { } std::unique_ptr DoClone() const override { +#if 1 + return nullptr; +#else PYBIND11_OVERLOAD_PURE(std::unique_ptr, Base, DoClone); +#endif } void DoRenderColorImage(ColorRenderCamera const& camera, diff --git a/bindings/pydrake/planning/planning_py_collision_checker.cc b/bindings/pydrake/planning/planning_py_collision_checker.cc index 67d473a78488..7cb266afc93f 100644 --- a/bindings/pydrake/planning/planning_py_collision_checker.cc +++ b/bindings/pydrake/planning/planning_py_collision_checker.cc @@ -286,6 +286,7 @@ void DefinePlanningCollisionChecker(py::module m) { m, "SceneGraphCollisionChecker", cls_doc.doc); // TODO(jwnimmer-tri) Bind the __init__(params=...) constructor here once // we've solved the unique_ptr vs shared_ptr binding lifetime issue. +#if 0 py::object params_ctor = m.attr("CollisionCheckerParams"); cls // BR .def(py::init([params_ctor](std::unique_ptr> model, @@ -309,8 +310,10 @@ void DefinePlanningCollisionChecker(py::module m) { "See :class:`pydrake.planning.CollisionCheckerParams` for the " "list of properties available here as kwargs.") .c_str()); +#endif } +#if 0 { using Class = UnimplementedCollisionChecker; constexpr auto& cls_doc = doc.UnimplementedCollisionChecker; @@ -344,6 +347,7 @@ void DefinePlanningCollisionChecker(py::module m) { "list of properties available here as kwargs.") .c_str()); } +#endif } } // namespace internal diff --git a/bindings/pydrake/systems/analysis_py.cc b/bindings/pydrake/systems/analysis_py.cc index 3540e0582f3a..47f566977bb5 100644 --- a/bindings/pydrake/systems/analysis_py.cc +++ b/bindings/pydrake/systems/analysis_py.cc @@ -237,12 +237,14 @@ PYBIND11_MODULE(analysis, m) { auto cls = DefineTemplateClassWithDefault>( m, "Simulator", GetPyParam(), doc.Simulator.doc); cls // BR +#if 0 .def(py::init&, unique_ptr>>(), py::arg("system"), py::arg("context") = nullptr, // Keep alive, reference: `self` keeps `system` alive. py::keep_alive<1, 2>(), // Keep alive, ownership: `context` keeps `self` alive. py::keep_alive<3, 1>(), doc.Simulator.ctor.doc) +#endif .def("Initialize", &Simulator::Initialize, doc.Simulator.Initialize.doc, py::arg("params") = InitializeParams{}) @@ -307,11 +309,13 @@ Parameter ``interruptible``: py_rvp::reference_internal, doc.Simulator.get_mutable_context.doc) .def("has_context", &Simulator::has_context, doc.Simulator.has_context.doc) +#if 0 .def("reset_context", &Simulator::reset_context, py::arg("context"), // Keep alive, ownership: `context` keeps `self` alive. py::keep_alive<2, 1>(), doc.Simulator.reset_context.doc) // TODO(eric.cousineau): Bind `release_context` once some form of the // PR RobotLocomotion/pybind11#33 lands. Presently, it fails. +#endif .def("set_publish_every_time_step", &Simulator::set_publish_every_time_step, py::arg("publish"), doc.Simulator.set_publish_every_time_step.doc) @@ -398,6 +402,7 @@ Parameter ``interruptible``: using namespace drake::systems::analysis; constexpr auto& doc = pydrake_doc.drake.systems.analysis; +#if 0 m.def("RandomSimulation", WrapCallbacks([](const SimulatorFactory make_simulator, const ScalarSystemFunction& output, double final_time, @@ -407,6 +412,7 @@ Parameter ``interruptible``: }), py::arg("make_simulator"), py::arg("output"), py::arg("final_time"), py::arg("generator"), doc.RandomSimulation.doc); +#endif py::class_( m, "RandomSimulationResult", doc.RandomSimulationResult.doc) @@ -416,6 +422,7 @@ Parameter ``interruptible``: &RandomSimulationResult::generator_snapshot, doc.RandomSimulationResult.generator_snapshot.doc); +#if 0 // Note: This hard-codes `parallelism` to be off, since parallel execution // of Python systems on multiple threads was thought to be unsupported. It's // possible that with `py::call_guard` it would @@ -431,6 +438,7 @@ Parameter ``interruptible``: py::arg("make_simulator"), py::arg("output"), py::arg("final_time"), py::arg("num_samples"), py::arg("generator"), doc.MonteCarloSimulation.doc); +#endif { using Class = RegionOfAttractionOptions; diff --git a/bindings/pydrake/systems/controllers_py.cc b/bindings/pydrake/systems/controllers_py.cc index 0bc0588b1015..f65da657d804 100644 --- a/bindings/pydrake/systems/controllers_py.cc +++ b/bindings/pydrake/systems/controllers_py.cc @@ -170,6 +170,7 @@ PYBIND11_MODULE(controllers, m) { using Class = PidControlledSystem; constexpr auto& cls_doc = doc.PidControlledSystem; py::class_>(m, "PidControlledSystem", cls_doc.doc) +#if 0 .def(py::init>, double, double, double, int, int>(), py::arg("plant"), py::arg("kp"), py::arg("ki"), py::arg("kd"), @@ -201,6 +202,7 @@ PYBIND11_MODULE(controllers, m) { py::arg("plant_input_port_index") = 0, // Keep alive, ownership: `plant` keeps `self` alive. py::keep_alive<2, 1>(), cls_doc.ctor.doc_7args_vector_gains) +#endif .def("get_control_input_port", &Class::get_control_input_port, py_rvp::reference_internal, cls_doc.get_control_input_port.doc) .def("get_state_input_port", &Class::get_state_input_port, diff --git a/bindings/pydrake/systems/framework_py_semantics.cc b/bindings/pydrake/systems/framework_py_semantics.cc index 4d13722311c3..488f3fd52865 100644 --- a/bindings/pydrake/systems/framework_py_semantics.cc +++ b/bindings/pydrake/systems/framework_py_semantics.cc @@ -14,17 +14,11 @@ #include "drake/systems/framework/leaf_output_port.h" #include "drake/systems/framework/system_output.h" -using std::string; -using std::unique_ptr; -using std::vector; - namespace drake { namespace pydrake { namespace { -using AbstractValuePtrList = vector>; - // Given an InputPort or OutputPort as self, return self.Eval(context). In // python, always returns either a numpy.ndarray (when vector-valued) or the // unwrapped T in a Value (when abstract-valued). @@ -102,7 +96,10 @@ void DoScalarIndependentDefinitions(py::module m) { DefClone(&abstract_values); abstract_values // BR .def(py::init<>(), doc.AbstractValues.ctor.doc_0args) - .def(py::init(), doc.AbstractValues.ctor.doc_1args) +#if 0 + .def(py::init>>(), + doc.AbstractValues.ctor.doc_1args) +#endif .def("size", &AbstractValues::size, doc.AbstractValues.size.doc) .def("get_value", &AbstractValues::get_value, py::arg("index"), py_rvp::reference_internal, doc.AbstractValues.get_value.doc) @@ -203,11 +200,13 @@ void DoScalarIndependentDefinitions(py::module m) { using Class = ValueProducer; constexpr auto& cls_doc = doc.ValueProducer; py::class_(m, "ValueProducer", cls_doc.doc) +#if 0 .def(py::init(WrapCallbacks([](ValueProducer::AllocateCallback allocate, ValueProducer::CalcCallback calc) { return Class(allocate, calc); })), py::arg("allocate"), py::arg("calc"), cls_doc.ctor.doc_overload_5d) +#endif .def_static("NoopCalc", &Class::NoopCalc, cls_doc.NoopCalc.doc); } @@ -587,8 +586,13 @@ void DoScalarDependentDefinitions(py::module m) { .def(py::init<>(), doc.DiagramBuilder.ctor.doc) .def( "AddSystem", - [](DiagramBuilder* self, unique_ptr> system) { + [](DiagramBuilder* self, std::shared_ptr> system) { +#if 1 + (void)(self); + (void)(system); +#else return self->AddSystem(std::move(system)); +#endif }, py::arg("system"), // TODO(eric.cousineau): These two keep_alive's purposely form a @@ -601,8 +605,14 @@ void DoScalarDependentDefinitions(py::module m) { .def( "AddNamedSystem", [](DiagramBuilder* self, std::string& name, - unique_ptr> system) { + std::shared_ptr> system) { +#if 1 + (void)(self); + (void)(name); + (void)(system); +#else return self->AddNamedSystem(name, std::move(system)); +#endif }, py::arg("name"), py::arg("system"), // TODO(eric.cousineau): These two keep_alive's purposely form a @@ -838,24 +848,26 @@ void DoScalarDependentDefinitions(py::module m) { auto parameters = DefineTemplateClassWithDefault>( m, "Parameters", GetPyParam(), doc.Parameters.doc); DefClone(¶meters); - using BasicVectorPtrList = vector>>; parameters .def(py::init<>(), doc.Parameters.ctor.doc_0args) +#if 0 // TODO(eric.cousineau): Ensure that we can respect keep alive behavior // with lists of pointers. - .def(py::init(), + .def(py::init>>, + std::vector>>(), py::arg("numeric"), py::arg("abstract"), doc.Parameters.ctor.doc_2args_numeric_abstract) - .def(py::init(), py::arg("numeric"), - doc.Parameters.ctor.doc_1args_numeric) - .def(py::init(), py::arg("abstract"), - doc.Parameters.ctor.doc_1args_abstract) - .def(py::init>>(), py::arg("vec"), + .def(py::init>>>(), + py::arg("numeric"), doc.Parameters.ctor.doc_1args_numeric) + .def(py::init>>(), + py::arg("abstract"), doc.Parameters.ctor.doc_1args_abstract) + .def(py::init>>(), py::arg("vec"), // Keep alive, ownership: `vec` keeps `self` alive. py::keep_alive<2, 1>(), doc.Parameters.ctor.doc_1args_vec) - .def(py::init>(), py::arg("value"), + .def(py::init>(), py::arg("value"), // Keep alive, ownership: `value` keeps `self` alive. py::keep_alive<2, 1>(), doc.Parameters.ctor.doc_1args_value) +#endif .def("num_numeric_parameter_groups", &Parameters::num_numeric_parameter_groups, doc.Parameters.num_numeric_parameter_groups.doc) @@ -870,6 +882,7 @@ void DoScalarDependentDefinitions(py::module m) { doc.Parameters.get_mutable_numeric_parameter.doc) .def("get_numeric_parameters", &Parameters::get_numeric_parameters, py_rvp::reference_internal, doc.Parameters.get_numeric_parameters.doc) +#if 0 // TODO(eric.cousineau): Should this C++ code constrain the number of // parameters??? .def("set_numeric_parameters", &Parameters::set_numeric_parameters, @@ -878,6 +891,7 @@ void DoScalarDependentDefinitions(py::module m) { // Keep alive, ownership: `value` keeps `self` alive. py::keep_alive<2, 1>(), py::arg("numeric_params"), doc.Parameters.set_numeric_parameters.doc) +#endif .def( "get_abstract_parameter", [](const Parameters* self, int index) -> auto& { @@ -895,12 +909,14 @@ void DoScalarDependentDefinitions(py::module m) { .def("get_abstract_parameters", &Parameters::get_abstract_parameters, py_rvp::reference_internal, doc.Parameters.get_abstract_parameters.doc) +#if 0 .def("set_abstract_parameters", &Parameters::set_abstract_parameters, // WARNING: This will DELETE the existing parameters. See C++ // `AddValueInstantiation` for more information. // Keep alive, ownership: `value` keeps `self` alive. py::keep_alive<2, 1>(), py::arg("abstract_params"), doc.Parameters.set_abstract_parameters.doc) +#endif .def( "SetFrom", [](Parameters* self, const Parameters& other) { @@ -961,12 +977,14 @@ void DoScalarDependentDefinitions(py::module m) { m, "ContinuousState", GetPyParam(), doc.ContinuousState.doc); DefClone(&continuous_state); continuous_state +#if 0 .def(py::init>>(), py::arg("state"), doc.ContinuousState.ctor.doc_1args_state) .def(py::init>, int, int, int>(), py::arg("state"), py::arg("num_q"), py::arg("num_v"), py::arg("num_z"), doc.ContinuousState.ctor.doc_4args_state_num_q_num_v_num_z) +#endif .def(py::init<>(), doc.ContinuousState.ctor.doc_0args) .def("size", &ContinuousState::size, doc.ContinuousState.size.doc) .def("num_q", &ContinuousState::num_q, doc.ContinuousState.num_q.doc) @@ -1026,10 +1044,12 @@ void DoScalarDependentDefinitions(py::module m) { m, "DiscreteValues", GetPyParam(), doc.DiscreteValues.doc); DefClone(&discrete_values); discrete_values +#if 0 .def(py::init>>(), py::arg("datum"), doc.DiscreteValues.ctor.doc_1args_datum) .def(py::init>>&&>(), py::arg("data"), doc.DiscreteValues.ctor.doc_1args_data) +#endif .def(py::init<>(), doc.DiscreteValues.ctor.doc_0args) .def("num_groups", &DiscreteValues::num_groups, doc.DiscreteValues.num_groups.doc) diff --git a/bindings/pydrake/systems/framework_py_systems.cc b/bindings/pydrake/systems/framework_py_systems.cc index 81737d72adfd..d4f1ecc56a29 100644 --- a/bindings/pydrake/systems/framework_py_systems.cc +++ b/bindings/pydrake/systems/framework_py_systems.cc @@ -561,8 +561,10 @@ Note: The above is for the C++ documentation. For Python, use }; type_visit(def_to_scalar_type_maybe, CommonScalarPack{}); +#if 0 using AllocCallback = typename LeafOutputPort::AllocCallback; using CalcCallback = typename LeafOutputPort::CalcCallback; +#endif using CalcVectorCallback = typename LeafOutputPort::CalcVectorCallback; auto leaf_system_cls = @@ -591,6 +593,7 @@ Note: The above is for the C++ documentation. For Python, use doc.LeafSystem.DeclareAbstractParameter.doc) .def("DeclareNumericParameter", &PyLeafSystem::DeclareNumericParameter, py::arg("model_vector"), doc.LeafSystem.DeclareNumericParameter.doc) +#if 0 .def("DeclareAbstractOutputPort", WrapCallbacks([](PyLeafSystem* self, const std::string& name, AllocCallback arg1, CalcCallback arg2, @@ -604,6 +607,7 @@ Note: The above is for the C++ documentation. For Python, use std::set{SystemBase::all_sources_ticket()}, doc.LeafSystem.DeclareAbstractOutputPort .doc_4args_name_alloc_function_calc_function_prerequisites_of_calc) +#endif .def( "DeclareVectorInputPort", [](PyLeafSystem* self, std::string name, @@ -1223,6 +1227,7 @@ void DoScalarIndependentDefinitions(py::module m) { &SystemScalarConverter::IsConvertible, GetPyParam(), cls_doc.IsConvertible.doc); using system_scalar_converter_internal::AddPydrakeConverterFunction; +#if 0 using ConverterFunction = std::function>(const System&)>; AddTemplateMethod(converter, "_Add", @@ -1235,6 +1240,7 @@ void DoScalarIndependentDefinitions(py::module m) { AddPydrakeConverterFunction(self, bare_func); }), GetPyParam()); +#endif }; // N.B. When changing the pairs of supported types below, ensure that these // reflect the stanzas for the advanced constructor of