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

pydrake systems: Expose initial round of different scalar types #8665

14 changes: 14 additions & 0 deletions bindings/pydrake/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -207,11 +207,25 @@ drake_py_library(
srcs = ["test/algebra_test_util.py"],
)

# Test ODR (One Definition Rule).
drake_pybind_library(
name = "autodiffutils_test_util_py",
testonly = 1,
add_install = False,
cc_deps = [
":autodiff_types_pybind",
],
cc_so_name = "test/autodiffutils_test_util",
cc_srcs = ["test/autodiffutils_test_util_py.cc"],
package_info = PACKAGE_INFO,
)

drake_py_unittest(
name = "autodiffutils_test",
deps = [
":algebra_test_util_py",
":autodiffutils_py",
":autodiffutils_test_util_py",
],
)

Expand Down
1 change: 1 addition & 0 deletions bindings/pydrake/autodiff_types_pybind.h
Original file line number Diff line number Diff line change
@@ -1,6 +1,7 @@
#pragma once

#include <Eigen/Core>
#include "pybind11/eigen.h"
#include "pybind11/pybind11.h"

#include "drake/bindings/pydrake/pydrake_pybind.h"
Expand Down
4 changes: 4 additions & 0 deletions bindings/pydrake/autodiffutils_py.cc
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,7 @@ PYBIND11_MODULE(_autodiffutils_py, m) {

py::class_<AutoDiffXd> autodiff(m, "AutoDiffXd");
autodiff
.def(py::init<double>())
.def(py::init<const double&, const Eigen::VectorXd&>())
.def("value", [](const AutoDiffXd& self) {
return self.value();
Expand Down Expand Up @@ -74,6 +75,9 @@ PYBIND11_MODULE(_autodiffutils_py, m) {
}, py::is_operator())
.def("__abs__", [](const AutoDiffXd& x) { return abs(x); });

py::implicitly_convertible<double, AutoDiffXd>();
py::implicitly_convertible<int, AutoDiffXd>();

// Add overloads for `math` functions.
auto math = py::module::import("pydrake.math");
MirrorDef<py::module, decltype(autodiff)>(&math, &autodiff)
Expand Down
29 changes: 29 additions & 0 deletions bindings/pydrake/pydrake_pybind.h
Original file line number Diff line number Diff line change
Expand Up @@ -12,13 +12,42 @@ namespace pydrake {
/**
@page python_bindings Python Bindings

# Overview

Drake uses [pybind11](http://pybind11.readthedocs.io/en/stable/) for binding
its C++ API to Python.

At present, a fork of `pybind11` is used which permits bindings matrices with
`dtype=object`, passing `unique_ptr` objects, and prevents aliasing for Python
classes derived from `pybind11` classes.

## `pybind11` Tips

### Python Types

Throughout the Drake code, Python types provided by `pybind11` are used, such
as `py::handle`, `py::object`, `py::module`, `py::str`, `py::list`, etc.
For an overview, see the
[pybind11 reference](http://pybind11.readthedocs.io/en/stable/reference.html).

All of these are effectively thin wrappers around `PyObject*`, and thus can be
cheaply copied.

Mutating the referred-to object also does not require passing by reference, so
you can always pass the object by value for functions, but you should document
your method if it mutates the object in a non-obvious fashion.

### Python Type Conversions

You can implicit convert between `py::object` and its derived classes (such
as `py::list`, `py::class_`, etc.), assuming the actual Python types agree.
You may also implicitly convert from `py::object` (and its derived classes) to
`py::handle`.

If you wish to convert a `py::handle` (or `PyObject*`) to `py::object` or a
derived class, you should use
[`py::reinterpret_borrow<>`](http://pybind11.readthedocs.io/en/stable/reference.html#_CPPv218reinterpret_borrow6handle).

# Conventions

## Target Conventions
Expand Down
2 changes: 1 addition & 1 deletion bindings/pydrake/solvers/mathematicalprogram_py.cc
Original file line number Diff line number Diff line change
Expand Up @@ -258,7 +258,7 @@ PYBIND11_MODULE(_mathematicalprogram_py, m) {
&MathematicalProgram::AddBoundingBoxConstraint))
.def("AddBoundingBoxConstraint",
[](MathematicalProgram* self, double lb, double ub,
const Eigen::Ref<MatrixX<symbolic::Variable>>& vars) {
const Eigen::Ref<const MatrixX<symbolic::Variable>>& vars) {
return self->AddBoundingBoxConstraint(lb, ub, vars);
})
.def("AddConstraint",
Expand Down
12 changes: 11 additions & 1 deletion bindings/pydrake/systems/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,11 @@ drake_py_library(
drake_cc_library(
name = "systems_pybind",
hdrs = ["systems_pybind.h"],
deps = ["//bindings/pydrake/util:cpp_template_pybind"],
deps = [
"//bindings/pydrake:autodiff_types_pybind",
"//bindings/pydrake:symbolic_types_pybind",
"//bindings/pydrake/util:cpp_template_pybind",
],
)

drake_pybind_library(
Expand All @@ -68,13 +72,16 @@ drake_pybind_library(
package_info = PACKAGE_INFO,
py_deps = [
":module_py",
"//bindings/pydrake:autodiffutils_py",
"//bindings/pydrake:symbolic_py",
"//bindings/pydrake/util:cpp_template_py",
],
)

drake_pybind_library(
name = "primitives_py",
cc_deps = [
":systems_pybind",
"//bindings/pydrake/util:drake_optional_pybind",
],
cc_so_name = "primitives",
Expand All @@ -88,6 +95,9 @@ drake_pybind_library(

drake_pybind_library(
name = "analysis_py",
cc_deps = [
":systems_pybind",
],
cc_so_name = "analysis",
cc_srcs = ["analysis_py.cc"],
package_info = PACKAGE_INFO,
Expand Down
84 changes: 46 additions & 38 deletions bindings/pydrake/systems/analysis_py.cc
Original file line number Diff line number Diff line change
@@ -1,6 +1,7 @@
#include "pybind11/pybind11.h"

#include "drake/bindings/pydrake/pydrake_pybind.h"
#include "drake/bindings/pydrake/systems/systems_pybind.h"
#include "drake/systems/analysis/integrator_base.h"
#include "drake/systems/analysis/simulator.h"

Expand All @@ -15,44 +16,51 @@ PYBIND11_MODULE(analysis, m) {

m.doc() = "Bindings for the analysis portion of the Systems framework.";

using T = double;

py::class_<IntegratorBase<T>>(m, "IntegratorBase")
.def("set_fixed_step_mode", &IntegratorBase<T>::set_fixed_step_mode)
.def("get_fixed_step_mode", &IntegratorBase<T>::get_fixed_step_mode)
.def("set_target_accuracy", &IntegratorBase<T>::set_target_accuracy)
.def("get_target_accuracy", &IntegratorBase<T>::get_target_accuracy)
.def("set_maximum_step_size", &IntegratorBase<T>::set_maximum_step_size)
.def("get_maximum_step_size", &IntegratorBase<T>::get_maximum_step_size)
.def("set_requested_minimum_step_size",
&IntegratorBase<T>::set_requested_minimum_step_size)
.def("get_requested_minimum_step_size",
&IntegratorBase<T>::get_requested_minimum_step_size)
.def("set_throw_on_minimum_step_size_violation",
&IntegratorBase<T>::set_throw_on_minimum_step_size_violation)
.def("get_throw_on_minimum_step_size_violation",
&IntegratorBase<T>::get_throw_on_minimum_step_size_violation);

py::class_<Simulator<T>>(m, "Simulator")
.def(py::init<const System<T>&>(),
// Keep alive, reference: `self` keeps `System` alive.
py::keep_alive<1, 2>())
.def(py::init<const System<T>&, unique_ptr<Context<T>>>(),
// Keep alive, reference: `self` keeps `System` alive.
py::keep_alive<1, 2>(),
// Keep alive, ownership: `Context` keeps `self` alive.
py::keep_alive<3, 1>())
.def("Initialize", &Simulator<T>::Initialize)
.def("StepTo", &Simulator<T>::StepTo)
.def("get_context", &Simulator<T>::get_context, py_reference_internal)
.def("get_integrator", &Simulator<T>::get_integrator, py_reference_internal)
.def("get_mutable_integrator", &Simulator<T>::get_mutable_integrator,
py_reference_internal)
.def("get_mutable_context", &Simulator<T>::get_mutable_context,
py_reference_internal)
.def("set_publish_every_time_step",
&Simulator<T>::set_publish_every_time_step)
.def("set_target_realtime_rate", &Simulator<T>::set_target_realtime_rate);
py::module::import("pydrake.systems.framework");

auto bind_scalar_types = [m](auto dummy) {
using T = decltype(dummy);
DefineTemplateClassWithDefault<IntegratorBase<T>>(
m, "IntegratorBase", GetPyParam<T>())
.def("set_fixed_step_mode", &IntegratorBase<T>::set_fixed_step_mode)
.def("get_fixed_step_mode", &IntegratorBase<T>::get_fixed_step_mode)
.def("set_target_accuracy", &IntegratorBase<T>::set_target_accuracy)
.def("get_target_accuracy", &IntegratorBase<T>::get_target_accuracy)
.def("set_maximum_step_size", &IntegratorBase<T>::set_maximum_step_size)
.def("get_maximum_step_size", &IntegratorBase<T>::get_maximum_step_size)
.def("set_requested_minimum_step_size",
&IntegratorBase<T>::set_requested_minimum_step_size)
.def("get_requested_minimum_step_size",
&IntegratorBase<T>::get_requested_minimum_step_size)
.def("set_throw_on_minimum_step_size_violation",
&IntegratorBase<T>::set_throw_on_minimum_step_size_violation)
.def("get_throw_on_minimum_step_size_violation",
&IntegratorBase<T>::get_throw_on_minimum_step_size_violation);

DefineTemplateClassWithDefault<Simulator<T>>(
m, "Simulator", GetPyParam<T>())
.def(py::init<const System<T>&>(),
// Keep alive, reference: `self` keeps `System` alive.
py::keep_alive<1, 2>())
.def(py::init<const System<T>&, unique_ptr<Context<T>>>(),
// Keep alive, reference: `self` keeps `System` alive.
py::keep_alive<1, 2>(),
// Keep alive, ownership: `Context` keeps `self` alive.
py::keep_alive<3, 1>())
.def("Initialize", &Simulator<T>::Initialize)
.def("StepTo", &Simulator<T>::StepTo)
.def("get_context", &Simulator<T>::get_context, py_reference_internal)
.def("get_integrator", &Simulator<T>::get_integrator,
py_reference_internal)
.def("get_mutable_integrator", &Simulator<T>::get_mutable_integrator,
py_reference_internal)
.def("get_mutable_context", &Simulator<T>::get_mutable_context,
py_reference_internal)
.def("set_publish_every_time_step",
&Simulator<T>::set_publish_every_time_step)
.def("set_target_realtime_rate", &Simulator<T>::set_target_realtime_rate);
};
type_visit(bind_scalar_types, pysystems::NonSymbolicScalarPack{});
}

} // namespace pydrake
Expand Down
5 changes: 5 additions & 0 deletions bindings/pydrake/systems/framework_py.cc
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,11 @@ namespace pydrake {
PYBIND11_MODULE(framework, m) {
m.doc() = "Bindings for the core Systems framework.";

// Import autodiff and symbolic modules so that their types are declared for
// use as template parameters.
py::module::import("pydrake.autodiffutils");
py::module::import("pydrake.symbolic");

// Incorporate definitions as pieces (to speed up compilation).
DefineFrameworkPySystems(m);
DefineFrameworkPySemantics(m);
Expand Down
Loading