Drake
systems_pybind.h
Go to the documentation of this file.
1 #pragma once
2 
3 /// @file
4 /// Helpers for defining Python types within the Systems framework.
5 
6 #include <string>
7 
8 #include "drake/bindings/pydrake/autodiff_types_pybind.h"
9 #include "drake/bindings/pydrake/pydrake_pybind.h"
10 #include "drake/bindings/pydrake/symbolic_types_pybind.h"
11 #include "drake/bindings/pydrake/util/cpp_param_pybind.h"
12 #include "drake/bindings/pydrake/util/cpp_template_pybind.h"
13 #include "drake/common/drake_throw.h"
14 #include "drake/systems/framework/value.h"
15 
16 namespace drake {
17 namespace pydrake {
18 namespace pysystems {
19 
20 /// Binds `Clone` and Pythonic `__copy__` and `__deepcopy__` for a class.
21 template <typename PyClass>
22 void DefClone(PyClass* ppy_class) {
23  using Class = typename PyClass::type;
24  PyClass& py_class = *ppy_class;
25  py_class
26  .def("Clone", &Class::Clone)
27  .def("__copy__", &Class::Clone)
28  .def("__deepcopy__", [](const Class* self, py::dict /* memo */) {
29  return self->Clone();
30  });
31 }
32 
33 /// Defines an instantiation of `pydrake.systems.framework.Value[...]`. This is
34 /// only meant to bind `Value<T>` (or specializations thereof).
35 /// @prereq `T` must have already been exposed to `pybind11`.
36 /// @param scope Parent scope.
37 /// @tparam T Inner parameter of `Value<T>`.
38 /// @tparam Class Class to be bound. By default, `Value<T>` is used.
39 /// @returns Reference to the registered Python type.
40 template <typename T, typename Class = systems::Value<T>>
41 py::object AddValueInstantiation(py::module scope) {
42  py::class_<Class, systems::AbstractValue> py_class(
43  scope, TemporaryClassName<Class>().c_str());
44  // Only use copy (clone) construction.
45  // Ownership with `unique_ptr<T>` has some annoying caveats, and some are
46  // simplified by always copying.
47  // See docstring for `set_value` for presently unavoidable caveats.
48  py_class.def(py::init<const T&>());
49  // Define emplace constructor.
50  // TODO(eric.cousineau): This presently requires that `T` be aliased or
51  // registered. For things like `std::vector`, this fails. Consider alternative
52  // to retrieve Python type from T?
53  py::object py_T = GetPyParam<T>()[0];
54  py_class.def(py::init([py_T](py::args args, py::kwargs kwargs) {
55  // Use Python constructor for the bound type.
56  py::object py_v = py_T(*args, **kwargs);
57  // TODO(eric.cousineau): Use `unique_ptr` for custom types if it's ever a
58  // performance concern.
59  // Use `type_caster` so that we are not forced to copy T, which is not
60  // possible for non-movable types. This can be avoided if we bind a
61  // `cpp_function` accepting a reference. However, that may cause the Python
62  // instance to be double-initialized.
63  py::detail::type_caster<T> caster;
64  DRAKE_THROW_UNLESS(caster.load(py_v, false));
65  const T& v = caster; // Use implicit conversion from `type_caster<>`.
66  return new Class(v);
67  }));
68  // N.B. `reference_internal` for pybind POD types (int, str, etc.) does not
69  // really do anything meaningful.
70  // TODO(eric.cousineau): Add check to warn about this.
71  py_class
72  .def("get_value", &Class::get_value, py_reference_internal)
73  .def("get_mutable_value", &Class::get_mutable_value, py_reference_internal);
74  std::string set_value_docstring = "Replaces stored value with a new one.";
76  set_value_docstring += R"""(
77 
78 @note The value type for this class is non-copyable.
79 You should ensure that you do not have any dangling references to previous
80 values returned by `get_value` or `get_mutable_value`, because this memory will
81 be destroyed when it is replaced, since it is stored using `unique_ptr<>`.
82 )""";
83  }
84  py_class.def("set_value", &Class::set_value, set_value_docstring.c_str());
85  // Register instantiation.
86  py::module py_module = py::module::import("pydrake.systems.framework");
87  AddTemplateClass(py_module, "Value", py_class, GetPyParam<T>());
88  return py_class;
89 }
90 
91 /// Type pack defining common scalar types.
92 // N.B. This should be kept in sync with the `*_DEFAULT_SCALARS` macro in
93 // `default_scalars.h`.
95  double,
96  AutoDiffXd,
98  >;
99 
100 /// Type pack for non-symbolic common scalar types.
101 // N.B. This should be kept in sync with the `*_DEFAULT_NONSYMBOLIC_SCALARS`
102 // macro in `default_scalars.h`.
104  double,
105  AutoDiffXd
106  >;
107 
108 } // namespace pysystems
109 } // namespace pydrake
110 } // namespace drake
Eigen::AutoDiffScalar< Eigen::VectorXd > AutoDiffXd
An autodiff variable with a dynamic number of partials.
Definition: eigen_autodiff_types.h:22
double value
Definition: wrap_test_util_py.cc:12
Definition: automotive_demo.cc:90
py::object AddValueInstantiation(py::module scope)
Defines an instantiation of pydrake.systems.framework.Value[...].
Definition: systems_pybind.h:41
#define DRAKE_THROW_UNLESS(condition)
Evaluates condition and iff the value is false will throw an exception with a message showing at leas...
Definition: drake_throw.h:23
Provides a tag to pass a parameter packs for ease of inference.
Definition: type_pack.h:16
Represents a symbolic form of an expression.
Definition: symbolic_expression.h:172
py::object AddTemplateClass(py::handle scope, const std::string &name, py::handle py_class, py::tuple param)
Adds a template class instantiation.
Definition: cpp_template_pybind.h:65
void DefClone(PyClass *ppy_class)
Binds Clone and Pythonic __copy__ and __deepcopy__ for a class.
Definition: systems_pybind.h:22
const auto py_reference_internal
Shorthand alias to pybind for consistency.
Definition: pydrake_pybind.h:180