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

[workspace] Switch pybind11 to upstream #19250

Draft
wants to merge 6 commits into
base: master
Choose a base branch
from
Draft
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
19 changes: 19 additions & 0 deletions bindings/pydrake/common/wrap_pybind.h
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,7 @@
#include <string>
#include <type_traits>
#include <utility>
#include <variant>

#include "drake/bindings/pydrake/common/wrap_function.h"
#include "drake/bindings/pydrake/pydrake_pybind.h"
Expand Down Expand Up @@ -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<Class> or shared_ptr<Class> 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 <typename Class>
std::variant<std::unique_ptr<Class>, std::shared_ptr<Class>> TryCastUnique(
py::object&& x) {
if (x.is_none()) {
return std::unique_ptr<Class>{};
}
if (x.ref_count() == 1) {
Class* value = x.template cast<Class*>();
x.release();
return std::unique_ptr<Class>(value);
}
return x.template cast<std::shared_ptr<Class>>();
}

} // namespace pydrake
} // namespace drake
8 changes: 6 additions & 2 deletions bindings/pydrake/geometry/geometry_py_render.cc
Original file line number Diff line number Diff line change
Expand Up @@ -38,10 +38,10 @@ using systems::sensors::PixelType;

namespace {

class PyRenderEngine : public py::wrapper<RenderEngine> {
class PyRenderEngine : public wrapper<RenderEngine> {
public:
using Base = RenderEngine;
using BaseWrapper = py::wrapper<Base>;
using BaseWrapper = wrapper<Base>;
PyRenderEngine() : BaseWrapper() {}

void UpdateViewpoint(RigidTransformd const& X_WR) override {
Expand All @@ -64,7 +64,11 @@ class PyRenderEngine : public py::wrapper<RenderEngine> {
}

std::unique_ptr<RenderEngine> DoClone() const override {
#if 1
return nullptr;
#else
PYBIND11_OVERLOAD_PURE(std::unique_ptr<RenderEngine>, Base, DoClone);
#endif
}

void DoRenderColorImage(ColorRenderCamera const& camera,
Expand Down
4 changes: 4 additions & 0 deletions bindings/pydrake/planning/planning_py_collision_checker.cc
Original file line number Diff line number Diff line change
Expand Up @@ -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<RobotDiagram<double>> model,
Expand All @@ -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;
Expand Down Expand Up @@ -344,6 +347,7 @@ void DefinePlanningCollisionChecker(py::module m) {
"list of properties available here as kwargs.")
.c_str());
}
#endif
}

} // namespace internal
Expand Down
4 changes: 2 additions & 2 deletions bindings/pydrake/pydrake_doxygen.h
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
93 changes: 91 additions & 2 deletions bindings/pydrake/pydrake_pybind.h
Original file line number Diff line number Diff line change
Expand Up @@ -145,8 +145,97 @@ 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<py::dtype>(ptr);
}
py::pybind11_fail("Unsupported buffer format!");
}
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 <typename Base>
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<bool>(patient_);
}

py::object patient_;
bool leaked_{false};
};

} // 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<Type> \
: public ::drake::pydrake::npy_format_descriptor_object {}; \
} /* namespace detail */ \
} /* namespace pybind11 */
4 changes: 2 additions & 2 deletions bindings/pydrake/solvers/solvers_py_mathematicalprogram.cc
Original file line number Diff line number Diff line change
Expand Up @@ -221,9 +221,9 @@ void SetSolverOptionBySolverType(MathematicalProgram* self,
}

// pybind11 trampoline class to permit overriding virtual functions in Python.
class PySolverInterface : public py::wrapper<solvers::SolverInterface> {
class PySolverInterface : public wrapper<solvers::SolverInterface> {
public:
using Base = py::wrapper<solvers::SolverInterface>;
using Base = wrapper<solvers::SolverInterface>;

PySolverInterface() : Base() {}

Expand Down
8 changes: 8 additions & 0 deletions bindings/pydrake/systems/analysis_py.cc
Original file line number Diff line number Diff line change
Expand Up @@ -237,12 +237,14 @@ PYBIND11_MODULE(analysis, m) {
auto cls = DefineTemplateClassWithDefault<Simulator<T>>(
m, "Simulator", GetPyParam<T>(), doc.Simulator.doc);
cls // BR
#if 0
.def(py::init<const System<T>&, unique_ptr<Context<T>>>(),
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<T>::Initialize,
doc.Simulator.Initialize.doc,
py::arg("params") = InitializeParams{})
Expand Down Expand Up @@ -307,11 +309,13 @@ Parameter ``interruptible``:
py_rvp::reference_internal, doc.Simulator.get_mutable_context.doc)
.def("has_context", &Simulator<T>::has_context,
doc.Simulator.has_context.doc)
#if 0
.def("reset_context", &Simulator<T>::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<T>::set_publish_every_time_step, py::arg("publish"),
doc.Simulator.set_publish_every_time_step.doc)
Expand Down Expand Up @@ -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,
Expand All @@ -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_<RandomSimulationResult>(
m, "RandomSimulationResult", doc.RandomSimulationResult.doc)
Expand All @@ -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<py::gil_scoped_release>` it would
Expand All @@ -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;
Expand Down
2 changes: 2 additions & 0 deletions bindings/pydrake/systems/controllers_py.cc
Original file line number Diff line number Diff line change
Expand Up @@ -170,6 +170,7 @@ PYBIND11_MODULE(controllers, m) {
using Class = PidControlledSystem<double>;
constexpr auto& cls_doc = doc.PidControlledSystem;
py::class_<Class, Diagram<double>>(m, "PidControlledSystem", cls_doc.doc)
#if 0
.def(py::init<std::unique_ptr<System<double>>, double, double, double,
int, int>(),
py::arg("plant"), py::arg("kp"), py::arg("ki"), py::arg("kd"),
Expand Down Expand Up @@ -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,
Expand Down
Loading