-
Notifications
You must be signed in to change notification settings - Fork 1.3k
/
Copy pathref_cycle_pybind.h
90 lines (72 loc) · 3.16 KB
/
ref_cycle_pybind.h
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
#pragma once
#include "drake/bindings/pydrake/pydrake_pybind.h"
namespace drake {
namespace pydrake {
namespace internal {
/* pydrake::internal::ref_cycle is a custom call policy for pybind11.
For an overview of other call policies, See
https://pybind11.readthedocs.io/en/stable/advanced/functions.html#additional-call-policies
`ref_cycle` creates a reference count cycle that Python's cyclic garbage
collection can find and collect, once the cycle's objects are no longer
reachable.
Both peer objects must be pybind11 classes that were defined with the
dynamic_attr() annotation. If either of the peer objects is not defined with
pybind11::dynamic_attr(), the binding will raise an exception at the time the
function or method is called. The error message will complain about objects
not being tracked by garbage collection. By default pybind11 python objects
are not tracked; the dynamic_attr() annotation makes sure the objects are
tracked. Also, it ensures that the implementation of `ref_cycle` can create
and assign a new attribute dynamically, which is how the garbage collectible
bookkeeping is accomplished.
`ref_cycle` causes each object to refer to the other in a cycle. It is
bidirectional and symmetric. The order of the template arguments does not
matter.
Note the consequences for object lifetimes:
* M keeps N alive, and N keeps M alive.
* Neither object is destroyed until:
* both are unreachable, and
* garbage collection runs.
@tparam Peer0 an argument index
@tparam Peer1 an argument index
The argument index starts at 1; for methods, `self` is at index 1. Index 0
denotes the return value.
*/
template <size_t Peer0, size_t Peer1>
struct ref_cycle {};
/* This function is used in the template below to select peers by call/return
index. */
void ref_cycle_impl(size_t peer0, size_t peer1,
const pybind11::detail::function_call& call, pybind11::handle ret);
} // namespace internal
} // namespace pydrake
} // namespace drake
namespace pybind11 {
namespace detail {
// Provide a specialization of the pybind11 internal process_attribute
// template; this allows writing an annotation that works seamlessly in
// bindings definitions.
template <size_t Peer0, size_t Peer1>
class process_attribute<drake::pydrake::internal::ref_cycle<Peer0, Peer1>>
: public process_attribute_default<
drake::pydrake::internal::ref_cycle<Peer0, Peer1>> {
public:
// NOLINTNEXTLINE(runtime/references)
static void precall(function_call& call) {
// Only generate code if this invocation doesn't need the result.
if constexpr (!needs_result()) {
drake::pydrake::internal::ref_cycle_impl(Peer0, Peer1, call, handle());
}
}
// NOLINTNEXTLINE(runtime/references)
static void postcall(function_call& call, handle ret) {
// Only generate code if this invocation *does* need the result.
if constexpr (needs_result()) {
drake::pydrake::internal::ref_cycle_impl(Peer0, Peer1, call, ret);
}
}
private:
// Returns true if either template parameter denotes the return value.
static constexpr bool needs_result() { return Peer0 == 0 || Peer1 == 0; }
};
} // namespace detail
} // namespace pybind11