Skip to content

Commit

Permalink
[pydrake] Add function to make arbitrary ref cycles
Browse files Browse the repository at this point in the history
This patch adds internal::make_arbitrary_ref_cycle(), which will prove
useful for awkward bindings like those involving multiple return values.

While in the neighborhood, it also adds a few previously missing tests.
  • Loading branch information
rpoyner-tri committed Nov 11, 2024
1 parent f859518 commit 100ca39
Show file tree
Hide file tree
Showing 4 changed files with 87 additions and 26 deletions.
71 changes: 46 additions & 25 deletions bindings/pydrake/common/ref_cycle_pybind.cc
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,32 @@ void make_ref_cycle(handle p0, handle p1) {
make_link(p1, p0);
}

void check_and_make_ref_cycle(size_t peer0, handle p0, size_t peer1, handle p1,
std::function<std::string(size_t)> not_gc_message_function) {
// Returns false if the handle's value is None. Throws if the handle's value
// is not of a garbage-collectable type.
auto check_handle = [&](size_t n, handle p) -> bool {
if (p.is_none()) {
return false;
}
// Among the reasons the following check may fail is that one of the
// participating pybind11::class_ types does not declare
// pybind11::dynamic_attr().
if (!PyType_IS_GC(Py_TYPE(p.ptr()))) {
py::pybind11_fail(not_gc_message_function(n));
}
return true;
};
if (!check_handle(peer0, p0) || !check_handle(peer1, p1)) {
// At least one of the handles is None. We can't construct a ref-cycle, but
// neither should we complain. None variable values happen for any number of
// legitimate reasons; appearance of None doesn't imply a defective use of
// the ref_cycle policy.
return;
}
make_ref_cycle(p0, p1);
}

} // namespace

void ref_cycle_impl(
Expand All @@ -67,32 +93,27 @@ void ref_cycle_impl(
handle p0 = get_arg(peer0);
handle p1 = get_arg(peer1);

// Returns false if the handle's value is None. Throws if the handle's value
// is not of a garbage-collectable type.
auto check_handle = [&](size_t n, handle p) -> bool {
if (p.is_none()) {
return false;
}
// Among the reasons the following check may fail is that one of the
// participating pybind11::class_ types does not declare
// pybind11::dynamic_attr().
if (!PyType_IS_GC(Py_TYPE(p.ptr()))) {
py::pybind11_fail(fmt::format(
"Could not activate ref_cycle: object type at index {} for "
"function '{}' is not tracked by garbage collection. Was the object "
"defined with `pybind11::class_<...>(... pybind11::dynamic_attr())`?",
n, call.func.name));
}
return true;
auto not_gc_error = [&call](size_t n) -> std::string {
return fmt::format(
"Could not activate ref_cycle: object type at index {} for "
"function '{}' is not tracked by garbage collection. Was the object "
"defined with `pybind11::class_<...>(... pybind11::dynamic_attr())`?",
n, call.func.name);
};
if (!check_handle(peer0, p0) || !check_handle(peer1, p1)) {
// At least one of the handles is None. We can't construct a ref-cycle, but
// neither should we complain. A None variable value could happen for any
// number of legitimate reasons, and does not mean that the ref_cycle call
// policy is defective.
return;
}
make_ref_cycle(p0, p1);
check_and_make_ref_cycle(peer0, p0, peer1, p1, not_gc_error);
}

void make_arbitrary_ref_cycle(
handle p0, handle p1, const std::string& location_hint) {
auto not_gc_error = [&location_hint](size_t n) -> std::string {
return fmt::format(
"Could not activate arbitrary ref_cycle: object type at argument {} "
"for binding at '{}' is not tracked by garbage collection. Was the "
"object defined with `pybind11::class_<...>(... "
"pybind11::dynamic_attr())`?",
n, location_hint);
};
check_and_make_ref_cycle(0, p0, 1, p1, not_gc_error);
}

} // namespace internal
Expand Down
9 changes: 9 additions & 0 deletions bindings/pydrake/common/ref_cycle_pybind.h
Original file line number Diff line number Diff line change
@@ -1,5 +1,7 @@
#pragma once

#include <string>

#include "drake/bindings/pydrake/pydrake_pybind.h"

namespace drake {
Expand Down Expand Up @@ -51,6 +53,13 @@ struct ref_cycle {};
void ref_cycle_impl(size_t peer0, size_t peer1,
const py::detail::function_call& call, py::handle ret);

/* This function constructs a reference cycle from arbitrary handles. It may be
needed in special cases where the ordinary call-policy annotations won't work.
The `location_hint` will appear in any exception messages; it should help
developers locate where and why this function was called. */
void make_arbitrary_ref_cycle(
py::handle p0, py::handle p1, const std::string& location_hint);

} // namespace internal
} // namespace pydrake
} // namespace drake
Expand Down
19 changes: 18 additions & 1 deletion bindings/pydrake/common/test/ref_cycle_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,8 @@
import weakref

from pydrake.common.ref_cycle_test_util import (
NotDynamic, IsDynamic, invalid_arg_index, free_function, ouroboros)
arbitrary_bad, arbitrary_ok, free_function, invalid_arg_index, IsDynamic,
NotDynamic, ouroboros)
from pydrake.common.test_utilities.memory_test_util import actual_ref_count


Expand Down Expand Up @@ -56,12 +57,28 @@ def test_ouroboros(self):
self.assertEqual(len(dut._pydrake_internal_ref_cycle_peers), 1)
self.check_is_collectable_cycle(returned, dut)

def test_arbitrary_ok(self):
got = arbitrary_ok()
self.assertTrue(hasattr(got, '_pydrake_internal_ref_cycle_peers'))

def test_arbitrary_bad(self):
with self.assertRaisesRegex(RuntimeError,
".*IsDynamic::arbitrary_bad.*"):
arbitrary_bad()

def test_free_function(self):
p0 = IsDynamic()
p1 = IsDynamic()
free_function(p0, p1)
self.check_is_collectable_cycle(p0, p1)

def test_init_cycle(self):
# Cover the case where index 1 refers to the `self` of a py::init<>()
# binding.
other = IsDynamic()
dut = IsDynamic(other)
self.check_is_collectable_cycle(dut, other)

def test_not_dynamic_add(self):
dut = NotDynamic()
peer = IsDynamic()
Expand Down
14 changes: 14 additions & 0 deletions bindings/pydrake/common/test/ref_cycle_test_util_py.cc
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,7 @@ class TestDummyBase {
TestDummyBase(const TestDummyBase&) = default;
~TestDummyBase() = default;

explicit TestDummyBase(IsDynamic*) {}
void AddNot(NotDynamic*) {}
NotDynamic* ReturnNot() { return new NotDynamic(); }
NotDynamic* ReturnNullNot() { return nullptr; }
Expand Down Expand Up @@ -50,6 +51,7 @@ PYBIND11_MODULE(ref_cycle_test_util, m) {
using Class = IsDynamic;
py::class_<Class>(m, "IsDynamic", py::dynamic_attr())
.def(py::init<>())
.def(py::init<IsDynamic*>(), py::arg("thing"), ref_cycle<1, 2>())
.def("AddNot", &Class::AddNot)
.def("AddNotCycle", &Class::AddNot, ref_cycle<1, 2>())
.def("ReturnNot", &Class::ReturnNot)
Expand All @@ -71,6 +73,18 @@ PYBIND11_MODULE(ref_cycle_test_util, m) {
// Returns its argument and creates a self-cycle.
m.def(
"ouroboros", [](IsDynamic* x) { return x; }, ref_cycle<0, 1>());
m.def("arbitrary_ok", []() {
auto d1 = py::cast(new IsDynamic);
auto d2 = py::cast(new IsDynamic);
internal::make_arbitrary_ref_cycle(d1, d2, "IsDynamic::arbitrary_ok");
return d1;
});
m.def("arbitrary_bad", []() {
auto dyn = py::cast(new IsDynamic);
auto bad = py::cast(new NotDynamic);
internal::make_arbitrary_ref_cycle(dyn, bad, "IsDynamic::arbitrary_bad");
return dyn;
});
}

} // namespace pydrake
Expand Down

0 comments on commit 100ca39

Please sign in to comment.